00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #include "collada_urdf/collada_urdf.h"
00039 #include <map>
00040 #include <vector>
00041 #include <list>
00042 
00043 #include <dae.h>
00044 #include <dae/daeDocument.h>
00045 #include <dae/daeErrorHandler.h>
00046 #include <dae/domAny.h>
00047 #include <dom/domCOLLADA.h>
00048 #include <dom/domConstants.h>
00049 #include <dom/domElements.h>
00050 #include <dom/domTriangles.h>
00051 #include <dom/domTypes.h>
00052 #include <resource_retriever/retriever.h>
00053 #include <urdf/model.h>
00054 #include <urdf_model/pose.h>
00055 #include <angles/angles.h>
00056 #include <ros/assert.h>
00057 
00058 #include <boost/date_time/posix_time/posix_time.hpp>
00059 #include <boost/date_time/posix_time/posix_time_io.hpp>
00060 #include <boost/format.hpp>
00061 #include <boost/array.hpp>
00062 #include <boost/shared_ptr.hpp>
00063 #include <boost/scoped_ptr.hpp>
00064 
00065 #if defined(ASSIMP_UNIFIED_HEADER_NAMES)
00066 #include <assimp/scene.h>
00067 #include <assimp/LogStream.hpp>
00068 #include <assimp/DefaultLogger.hpp>
00069 #include <assimp/IOStream.hpp>
00070 #include <assimp/IOSystem.hpp>
00071 #include <assimp/Importer.hpp>
00072 #include <assimp/postprocess.h>
00073 #else
00074 #include <assimp.hpp>
00075 #include <aiScene.h>
00076 #include <aiPostProcess.h>
00077 #include <DefaultLogger.h>
00078 #include <IOStream.h>
00079 #include <IOSystem.h>
00080 #endif
00081 
00082 #include <geometric_shapes/shapes.h>
00083 #include <geometric_shapes/mesh_operations.h>
00084 
00085 #define FOREACH(it, v) for(typeof((v).begin())it = (v).begin(); it != (v).end(); (it)++)
00086 #define FOREACHC FOREACH
00087 
00088 using namespace std;
00089 
00090 namespace ColladaDOM150 { }
00091 
00092 namespace collada_urdf {
00093 
00094 using namespace ColladaDOM150;
00095 
00097 class ResourceIOStream : public Assimp::IOStream
00098 {
00099 public:
00100     ResourceIOStream(const resource_retriever::MemoryResource& res)
00101         : res_(res)
00102         , pos_(res.data.get())
00103     {
00104     }
00105 
00106     ~ResourceIOStream()
00107     {
00108     }
00109 
00110     size_t Read(void* buffer, size_t size, size_t count)
00111     {
00112         size_t to_read = size * count;
00113         if (pos_ + to_read > res_.data.get() + res_.size)
00114         {
00115             to_read = res_.size - (pos_ - res_.data.get());
00116         }
00117 
00118         memcpy(buffer, pos_, to_read);
00119         pos_ += to_read;
00120 
00121         return to_read;
00122     }
00123 
00124     size_t Write( const void* buffer, size_t size, size_t count) {
00125         ROS_BREAK(); return 0;
00126     }
00127 
00128     aiReturn Seek( size_t offset, aiOrigin origin)
00129     {
00130         uint8_t* new_pos = 0;
00131         switch (origin)
00132         {
00133         case aiOrigin_SET:
00134             new_pos = res_.data.get() + offset;
00135             break;
00136         case aiOrigin_CUR:
00137             new_pos = pos_ + offset; 
00138             break;
00139         case aiOrigin_END:
00140             new_pos = res_.data.get() + res_.size - offset; 
00141             break;
00142         default:
00143             ROS_BREAK();
00144         }
00145 
00146         if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size)
00147         {
00148             return aiReturn_FAILURE;
00149         }
00150 
00151         pos_ = new_pos;
00152         return aiReturn_SUCCESS;
00153     }
00154 
00155     size_t Tell() const
00156     {
00157         return pos_ - res_.data.get();
00158     }
00159 
00160     size_t FileSize() const
00161     {
00162         return res_.size;
00163     }
00164 
00165     void Flush() {
00166     }
00167 
00168 private:
00169     resource_retriever::MemoryResource res_;
00170     uint8_t* pos_;
00171 };
00172 
00173 namespace mathextra {
00174 
00175 
00176 const double g_fEpsilon = 1e-15;
00177 
00178 
00179 
00180 #define distinctRoots 0                       // roots r0 < r1 < r2
00181 #define singleRoot 1                       // root r0
00182 #define floatRoot01 2                       // roots r0 = r1 < r2
00183 #define floatRoot12 4                       // roots r0 < r1 = r2
00184 #define tripleRoot 6                       // roots r0 = r1 = r2
00185 
00186 
00187 template <typename T, typename S>
00188 void Tridiagonal3 (S* mat, T* diag, T* subd)
00189 {
00190     T a, b, c, d, e, f, ell, q;
00191 
00192     a = mat[0*3+0];
00193     b = mat[0*3+1];
00194     c = mat[0*3+2];
00195     d = mat[1*3+1];
00196     e = mat[1*3+2];
00197     f = mat[2*3+2];
00198 
00199     subd[2] = 0.0;
00200     diag[0] = a;
00201     if ( fabs(c) >= g_fEpsilon ) {
00202         ell = (T)sqrt(b*b+c*c);
00203         b /= ell;
00204         c /= ell;
00205         q = 2*b*e+c*(f-d);
00206         diag[1] = d+c*q;
00207         diag[2] = f-c*q;
00208         subd[0] = ell;
00209         subd[1] = e-b*q;
00210         mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (T)0;
00211         mat[1*3+0] = (S)0; mat[1*3+1] = b; mat[1*3+2] = c;
00212         mat[2*3+0] = (S)0; mat[2*3+1] = c; mat[2*3+2] = -b;
00213     }
00214     else {
00215         diag[1] = d;
00216         diag[2] = f;
00217         subd[0] = b;
00218         subd[1] = e;
00219         mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (S)0;
00220         mat[1*3+0] = (S)0; mat[1*3+1] = (S)1; mat[1*3+2] = (S)0;
00221         mat[2*3+0] = (S)0; mat[2*3+1] = (S)0; mat[2*3+2] = (S)1;
00222     }
00223 }
00224 
00225 int CubicRoots (double c0, double c1, double c2, double *r0, double *r1, double *r2)
00226 {
00227     
00228 
00229     int maxiter = 50;
00230     double discr, temp, pval, pdval, b0, b1;
00231     int i;
00232 
00233     
00234     discr = c2*c2-3*c1;
00235     if ( discr >= 0.0 ) {
00236         discr = (double)sqrt(discr);
00237         temp = (c2+discr)/3;
00238         pval = temp*(temp*(temp-c2)+c1)-c0;
00239         if ( pval >= 0.0 ) {
00240             
00241             (*r0) = (c2-discr)/3 - 1;  
00242             pval = 2*g_fEpsilon;
00243             for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) {
00244                 pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0;
00245                 pdval = (*r0)*(3*(*r0)-2*c2)+c1;
00246                 (*r0) -= pval/pdval;
00247             }
00248 
00249             
00250             
00251             b1 = (*r0)-c2;
00252             b0 = (*r0)*((*r0)-c2)+c1;
00253             discr = b1*b1-4*b0;
00254             if ( discr < -g_fEpsilon )
00255             {
00256                 
00257                 return singleRoot;
00258             }
00259             else
00260             {
00261                 int result = distinctRoots;
00262 
00263                 
00264                 discr = sqrt(fabs(discr));
00265                 (*r1) = 0.5f*(-b1-discr);
00266                 (*r2) = 0.5f*(-b1+discr);
00267 
00268                 if ( fabs((*r0)-(*r1)) <= g_fEpsilon )
00269                 {
00270                     (*r0) = (*r1);
00271                     result |= floatRoot01;
00272                 }
00273                 if ( fabs((*r1)-(*r2)) <= g_fEpsilon )
00274                 {
00275                     (*r1) = (*r2);
00276                     result |= floatRoot12;
00277                 }
00278                 return result;
00279             }
00280         }
00281         else {
00282             
00283             (*r2) = temp + 1;  
00284             pval = 2*g_fEpsilon;
00285             for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) {
00286                 pval = (*r2)*((*r2)*((*r2)-c2)+c1)-c0;
00287                 pdval = (*r2)*(3*(*r2)-2*c2)+c1;
00288                 (*r2) -= pval/pdval;
00289             }
00290 
00291             
00292             
00293             b1 = (*r2)-c2;
00294             b0 = (*r2)*((*r2)-c2)+c1;
00295             discr = b1*b1-4*b0;
00296             if ( discr < -g_fEpsilon )
00297             {
00298                 
00299                 (*r0) = (*r2);
00300                 return singleRoot;
00301             }
00302             else
00303             {
00304                 int result = distinctRoots;
00305 
00306                 
00307                 discr = sqrt(fabs(discr));
00308                 (*r0) = 0.5f*(-b1-discr);
00309                 (*r1) = 0.5f*(-b1+discr);
00310 
00311                 if ( fabs((*r0)-(*r1)) <= g_fEpsilon )
00312                 {
00313                     (*r0) = (*r1);
00314                     result |= floatRoot01;
00315                 }
00316                 if ( fabs((*r1)-(*r2)) <= g_fEpsilon )
00317                 {
00318                     (*r1) = (*r2);
00319                     result |= floatRoot12;
00320                 }
00321                 return result;
00322             }
00323         }
00324     }
00325     else {
00326         
00327         (*r0) = c0;
00328         pval = 2*g_fEpsilon;
00329         for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) {
00330             pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0;
00331             pdval = (*r0)*(3*(*r0)-2*c2)+c1;
00332             (*r0) -= pval/pdval;
00333         }
00334         return singleRoot;
00335     }
00336 }
00337 
00338 
00339 template <class T>
00340 bool _QLAlgorithm3 (T* m_aafEntry, T* afDiag, T* afSubDiag)
00341 {
00342     
00343     
00344 
00345     for (int i0 = 0; i0 < 3; i0++)
00346     {
00347         const int iMaxIter = 32;
00348         int iIter;
00349         for (iIter = 0; iIter < iMaxIter; iIter++)
00350         {
00351             int i1;
00352             for (i1 = i0; i1 <= 1; i1++)
00353             {
00354                 T fSum = fabs(afDiag[i1]) +
00355                          fabs(afDiag[i1+1]);
00356                 if ( fabs(afSubDiag[i1]) + fSum == fSum )
00357                     break;
00358             }
00359             if ( i1 == i0 )
00360                 break;
00361 
00362             T fTmp0 = (afDiag[i0+1]-afDiag[i0])/(2.0f*afSubDiag[i0]);
00363             T fTmp1 = sqrt(fTmp0*fTmp0+1.0f);
00364             if ( fTmp0 < 0.0f )
00365                 fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0-fTmp1);
00366             else
00367                 fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0+fTmp1);
00368             T fSin = 1.0f;
00369             T fCos = 1.0f;
00370             T fTmp2 = 0.0f;
00371             for (int i2 = i1-1; i2 >= i0; i2--)
00372             {
00373                 T fTmp3 = fSin*afSubDiag[i2];
00374                 T fTmp4 = fCos*afSubDiag[i2];
00375                 if ( fabs(fTmp3) >= fabs(fTmp0) )
00376                 {
00377                     fCos = fTmp0/fTmp3;
00378                     fTmp1 = sqrt(fCos*fCos+1.0f);
00379                     afSubDiag[i2+1] = fTmp3*fTmp1;
00380                     fSin = 1.0f/fTmp1;
00381                     fCos *= fSin;
00382                 }
00383                 else
00384                 {
00385                     fSin = fTmp3/fTmp0;
00386                     fTmp1 = sqrt(fSin*fSin+1.0f);
00387                     afSubDiag[i2+1] = fTmp0*fTmp1;
00388                     fCos = 1.0f/fTmp1;
00389                     fSin *= fCos;
00390                 }
00391                 fTmp0 = afDiag[i2+1]-fTmp2;
00392                 fTmp1 = (afDiag[i2]-fTmp0)*fSin+2.0f*fTmp4*fCos;
00393                 fTmp2 = fSin*fTmp1;
00394                 afDiag[i2+1] = fTmp0+fTmp2;
00395                 fTmp0 = fCos*fTmp1-fTmp4;
00396 
00397                 for (int iRow = 0; iRow < 3; iRow++)
00398                 {
00399                     fTmp3 = m_aafEntry[iRow*3+i2+1];
00400                     m_aafEntry[iRow*3+i2+1] = fSin*m_aafEntry[iRow*3+i2] +
00401                                               fCos*fTmp3;
00402                     m_aafEntry[iRow*3+i2] = fCos*m_aafEntry[iRow*3+i2] -
00403                                             fSin*fTmp3;
00404                 }
00405             }
00406             afDiag[i0] -= fTmp2;
00407             afSubDiag[i0] = fTmp0;
00408             afSubDiag[i1] = 0.0f;
00409         }
00410 
00411         if ( iIter == iMaxIter )
00412         {
00413             
00414             return false;
00415         }
00416     }
00417 
00418     return true;
00419 }
00420 
00421 bool QLAlgorithm3 (float* m_aafEntry, float* afDiag, float* afSubDiag)
00422 {
00423     return _QLAlgorithm3<float>(m_aafEntry, afDiag, afSubDiag);
00424 }
00425 
00426 bool QLAlgorithm3 (double* m_aafEntry, double* afDiag, double* afSubDiag)
00427 {
00428     return _QLAlgorithm3<double>(m_aafEntry, afDiag, afSubDiag);
00429 }
00430 
00431 void EigenSymmetric3(const double* fmat, double* afEigenvalue, double* fevecs)
00432 {
00433     double afSubDiag[3];
00434 
00435     memcpy(fevecs, fmat, sizeof(double)*9);
00436     Tridiagonal3(fevecs, afEigenvalue,afSubDiag);
00437     QLAlgorithm3(fevecs, afEigenvalue,afSubDiag);
00438 
00439     
00440     double fDet = fevecs[0*3+0] * (fevecs[1*3+1] * fevecs[2*3+2] - fevecs[1*3+2] * fevecs[2*3+1]) +
00441                   fevecs[0*3+1] * (fevecs[1*3+2] * fevecs[2*3+0] - fevecs[1*3+0] * fevecs[2*3+2]) +
00442                   fevecs[0*3+2] * (fevecs[1*3+0] * fevecs[2*3+1] - fevecs[1*3+1] * fevecs[2*3+0]);
00443     if ( fDet < 0.0f )
00444     {
00445         fevecs[0*3+2] = -fevecs[0*3+2];
00446         fevecs[1*3+2] = -fevecs[1*3+2];
00447         fevecs[2*3+2] = -fevecs[2*3+2];
00448     }
00449 }
00450 
00451 
00452 } 
00453 
00455 class ResourceIOSystem : public Assimp::IOSystem
00456 {
00457 public:
00458     ResourceIOSystem()
00459     {
00460     }
00461 
00462     ~ResourceIOSystem()
00463     {
00464     }
00465 
00466     
00467     bool Exists(const char* file) const
00468     {
00469         
00470         
00471         
00472         resource_retriever::MemoryResource res;
00473         try {
00474             res = retriever_.get(file);
00475         }
00476         catch (resource_retriever::Exception& e) {
00477             return false;
00478         }
00479 
00480         return true;
00481     }
00482 
00483     
00484     char getOsSeparator() const
00485     {
00486         return '/';
00487     }
00488 
00489     
00490     Assimp::IOStream* Open(const char* file, const char* mode)
00491     {
00492         ROS_ASSERT(mode == std::string("r") || mode == std::string("rb"));
00493 
00494         
00495         
00496         resource_retriever::MemoryResource res;
00497         try {
00498             res = retriever_.get(file);
00499         }
00500         catch (resource_retriever::Exception& e) {
00501             return 0;
00502         }
00503 
00504         return new ResourceIOStream(res);
00505     }
00506 
00507     void Close(Assimp::IOStream* stream) {
00508         delete stream;
00509     }
00510 
00511 private:
00512     mutable resource_retriever::Retriever retriever_;
00513 };
00514 
00515 class Triangle
00516 {
00517 public:
00518     Triangle(const urdf::Vector3 &_p1, const urdf::Vector3 &_p2, const urdf::Vector3 &_p3) :
00519       p1(_p1), p2(_p2), p3(_p3)
00520     {}
00521     Triangle() { this->clear(); };
00522     urdf::Vector3 p1, p2, p3;
00523 
00524     void clear() { p1.clear(); p2.clear(); p3.clear(); };
00525 };
00526 
00528 class ColladaWriter : public daeErrorHandler
00529 {
00530 private:
00531     struct SCENE
00532     {
00533         domVisual_sceneRef vscene;
00534         domKinematics_sceneRef kscene;
00535         domPhysics_sceneRef pscene;
00536         domInstance_with_extraRef viscene;
00537         domInstance_kinematics_sceneRef kiscene;
00538         domInstance_with_extraRef piscene;
00539     };
00540 
00541     typedef std::map< boost::shared_ptr<const urdf::Link>, urdf::Pose > MAPLINKPOSES;
00542     struct LINKOUTPUT
00543     {
00544         list<pair<int,string> > listusedlinks;
00545         list<pair<int,string> > listprocesseddofs;
00546         daeElementRef plink;
00547         domNodeRef pnode;
00548         MAPLINKPOSES _maplinkposes;
00549     };
00550 
00551     struct physics_model_output
00552     {
00553         domPhysics_modelRef pmodel;
00554         std::vector<std::string > vrigidbodysids;     
00555     };
00556 
00557     struct kinematics_model_output
00558     {
00559         struct axis_output
00560         {
00561             
00562             axis_output() : iaxis(0) {
00563             }
00564             string sid, nodesid;
00565             boost::shared_ptr<const urdf::Joint> pjoint;
00566             int iaxis;
00567             string jointnodesid;
00568         };
00569         domKinematics_modelRef kmodel;
00570         std::vector<axis_output> vaxissids;
00571         std::vector<std::string > vlinksids;
00572         MAPLINKPOSES _maplinkposes;
00573     };
00574 
00575     struct axis_sids
00576     {
00577         axis_sids(const string& axissid, const string& valuesid, const string& jointnodesid) : axissid(axissid), valuesid(valuesid), jointnodesid(jointnodesid) {
00578         }
00579         string axissid, valuesid, jointnodesid;
00580     };
00581 
00582     struct instance_kinematics_model_output
00583     {
00584         domInstance_kinematics_modelRef ikm;
00585         std::vector<axis_sids> vaxissids;
00586         boost::shared_ptr<kinematics_model_output> kmout;
00587         std::vector<std::pair<std::string,std::string> > vkinematicsbindings;
00588     };
00589 
00590     struct instance_articulated_system_output
00591     {
00592         domInstance_articulated_systemRef ias;
00593         std::vector<axis_sids> vaxissids;
00594         std::vector<std::string > vlinksids;
00595         std::vector<std::pair<std::string,std::string> > vkinematicsbindings;
00596     };
00597 
00598     struct instance_physics_model_output
00599     {
00600         domInstance_physics_modelRef ipm;
00601         boost::shared_ptr<physics_model_output> pmout;
00602     };
00603 
00604     struct kinbody_models
00605     {
00606         std::string uri, kinematicsgeometryhash;
00607         boost::shared_ptr<kinematics_model_output> kmout;
00608         boost::shared_ptr<physics_model_output> pmout;
00609     };
00610 
00611 public:
00612     ColladaWriter(const urdf::Model& robot, int writeoptions) : _writeoptions(writeoptions), _robot(robot), _dom(NULL) {
00613         daeErrorHandler::setErrorHandler(this);
00614         _importer.SetIOHandler(new ResourceIOSystem());
00615     }
00616     virtual ~ColladaWriter() {
00617     }
00618 
00619     daeDocument* doc() {
00620         return _doc;
00621     }
00622 
00623     bool convert()
00624     {
00625         try {
00626             const char* documentName = "urdf_snapshot";
00627             daeInt error = _collada.getDatabase()->insertDocument(documentName, &_doc ); 
00628             if (error != DAE_OK || _doc == NULL) {
00629                 throw ColladaUrdfException("Failed to create document");
00630             }
00631             _dom = daeSafeCast<domCOLLADA>(_doc->getDomRoot());
00632             _dom->setAttribute("xmlns:math","http://www.w3.org/1998/Math/MathML");
00633 
00634             
00635             domAssetRef asset = daeSafeCast<domAsset>( _dom->add( COLLADA_ELEMENT_ASSET ) );
00636             {
00637                 
00638                 boost::posix_time::time_facet* facet = new boost::posix_time::time_facet("%Y-%m-%dT%H:%M:%s");
00639                 std::stringstream ss;
00640                 ss.imbue(std::locale(ss.getloc(), facet));
00641                 ss << boost::posix_time::second_clock::local_time();
00642 
00643                 domAsset::domCreatedRef created = daeSafeCast<domAsset::domCreated>( asset->add( COLLADA_ELEMENT_CREATED ) );
00644                 created->setValue(ss.str().c_str());
00645                 domAsset::domModifiedRef modified = daeSafeCast<domAsset::domModified>( asset->add( COLLADA_ELEMENT_MODIFIED ) );
00646                 modified->setValue(ss.str().c_str());
00647 
00648                 domAsset::domContributorRef contrib = daeSafeCast<domAsset::domContributor>( asset->add( COLLADA_TYPE_CONTRIBUTOR ) );
00649                 domAsset::domContributor::domAuthoring_toolRef authoringtool = daeSafeCast<domAsset::domContributor::domAuthoring_tool>( contrib->add( COLLADA_ELEMENT_AUTHORING_TOOL ) );
00650                 authoringtool->setValue("URDF Collada Writer");
00651 
00652                 domAsset::domUnitRef units = daeSafeCast<domAsset::domUnit>( asset->add( COLLADA_ELEMENT_UNIT ) );
00653                 units->setMeter(1);
00654                 units->setName("meter");
00655 
00656                 domAsset::domUp_axisRef zup = daeSafeCast<domAsset::domUp_axis>( asset->add( COLLADA_ELEMENT_UP_AXIS ) );
00657                 zup->setValue(UP_AXIS_Z_UP);
00658             }
00659 
00660             _globalscene = _dom->getScene();
00661             if( !_globalscene ) {
00662                 _globalscene = daeSafeCast<domCOLLADA::domScene>( _dom->add( COLLADA_ELEMENT_SCENE ) );
00663             }
00664 
00665             _visualScenesLib = daeSafeCast<domLibrary_visual_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_VISUAL_SCENES));
00666             _visualScenesLib->setId("vscenes");
00667             _geometriesLib = daeSafeCast<domLibrary_geometries>(_dom->add(COLLADA_ELEMENT_LIBRARY_GEOMETRIES));
00668             _geometriesLib->setId("geometries");
00669             _effectsLib = daeSafeCast<domLibrary_effects>(_dom->add(COLLADA_ELEMENT_LIBRARY_EFFECTS));
00670             _effectsLib->setId("effects");
00671             _materialsLib = daeSafeCast<domLibrary_materials>(_dom->add(COLLADA_ELEMENT_LIBRARY_MATERIALS));
00672             _materialsLib->setId("materials");
00673             _kinematicsModelsLib = daeSafeCast<domLibrary_kinematics_models>(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_MODELS));
00674             _kinematicsModelsLib->setId("kmodels");
00675             _articulatedSystemsLib = daeSafeCast<domLibrary_articulated_systems>(_dom->add(COLLADA_ELEMENT_LIBRARY_ARTICULATED_SYSTEMS));
00676             _articulatedSystemsLib->setId("asystems");
00677             _kinematicsScenesLib = daeSafeCast<domLibrary_kinematics_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_SCENES));
00678             _kinematicsScenesLib->setId("kscenes");
00679             _physicsScenesLib = daeSafeCast<domLibrary_physics_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_SCENES));
00680             _physicsScenesLib->setId("pscenes");
00681             _physicsModelsLib = daeSafeCast<domLibrary_physics_models>(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_MODELS));
00682             _physicsModelsLib->setId("pmodels");
00683             domExtraRef pextra_library_sensors = daeSafeCast<domExtra>(_dom->add(COLLADA_ELEMENT_EXTRA));
00684             pextra_library_sensors->setId("sensors");
00685             pextra_library_sensors->setType("library_sensors");
00686             _sensorsLib = daeSafeCast<domTechnique>(pextra_library_sensors->add(COLLADA_ELEMENT_TECHNIQUE));
00687             _sensorsLib->setProfile("OpenRAVE"); 
00688 
00689             _CreateScene();
00690             _WritePhysics();
00691             _WriteRobot();
00692             _WriteBindingsInstance_kinematics_scene();
00693             return true;
00694         }
00695         catch (ColladaUrdfException ex) {
00696             ROS_ERROR("Error converting: %s", ex.what());
00697             return false;
00698         }
00699     }
00700 
00701     bool writeTo(string const& file) {
00702         try {
00703             daeString uri = _doc->getDocumentURI()->getURI();
00704             _collada.writeTo(uri, file);
00705         } catch (ColladaUrdfException ex) {
00706             return false;
00707         }
00708         return true;
00709     }
00710 
00711 protected:
00712     virtual void handleError(daeString msg) {
00713         throw ColladaUrdfException(msg);
00714     }
00715     virtual void handleWarning(daeString msg) {
00716         std::cerr << "COLLADA DOM warning: " << msg << std::endl;
00717     }
00718 
00719     void _CreateScene()
00720     {
00721         
00722         _scene.vscene = daeSafeCast<domVisual_scene>(_visualScenesLib->add(COLLADA_ELEMENT_VISUAL_SCENE));
00723         _scene.vscene->setId("vscene");
00724         _scene.vscene->setName("URDF Visual Scene");
00725 
00726         
00727         _scene.kscene = daeSafeCast<domKinematics_scene>(_kinematicsScenesLib->add(COLLADA_ELEMENT_KINEMATICS_SCENE));
00728         _scene.kscene->setId("kscene");
00729         _scene.kscene->setName("URDF Kinematics Scene");
00730 
00731         
00732         _scene.pscene = daeSafeCast<domPhysics_scene>(_physicsScenesLib->add(COLLADA_ELEMENT_PHYSICS_SCENE));
00733         _scene.pscene->setId("pscene");
00734         _scene.pscene->setName("URDF Physics Scene");
00735 
00736         
00737         _scene.viscene = daeSafeCast<domInstance_with_extra>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_VISUAL_SCENE ));
00738         _scene.viscene->setUrl( (string("#") + string(_scene.vscene->getID())).c_str() );
00739 
00740         
00741         _scene.kiscene = daeSafeCast<domInstance_kinematics_scene>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_KINEMATICS_SCENE ));
00742         _scene.kiscene->setUrl( (string("#") + string(_scene.kscene->getID())).c_str() );
00743 
00744         
00745         _scene.piscene = daeSafeCast<domInstance_with_extra>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_PHYSICS_SCENE ));
00746         _scene.piscene->setUrl( (string("#") + string(_scene.pscene->getID())).c_str() );
00747     }
00748 
00749     void _WritePhysics() {
00750         domPhysics_scene::domTechnique_commonRef common = daeSafeCast<domPhysics_scene::domTechnique_common>(_scene.pscene->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00751         
00752         domTargetable_float3Ref g = daeSafeCast<domTargetable_float3>(common->add(COLLADA_ELEMENT_GRAVITY));
00753         g->getValue().set3 (0,0,0);
00754     }
00755 
00757     void _WriteRobot(int id = 0)
00758     {
00759         ROS_DEBUG_STREAM(str(boost::format("writing robot as instance_articulated_system (%d) %s\n")%id%_robot.getName()));
00760         string asid = _ComputeId(str(boost::format("robot%d")%id));
00761         string askid = _ComputeId(str(boost::format("%s_kinematics")%asid));
00762         string asmid = _ComputeId(str(boost::format("%s_motion")%asid));
00763         string iassid = _ComputeId(str(boost::format("%s_inst")%asmid));
00764 
00765         domInstance_articulated_systemRef ias = daeSafeCast<domInstance_articulated_system>(_scene.kscene->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM));
00766         ias->setSid(iassid.c_str());
00767         ias->setUrl((string("#")+asmid).c_str());
00768         ias->setName(_robot.getName().c_str());
00769 
00770         _iasout.reset(new instance_articulated_system_output());
00771         _iasout->ias = ias;
00772 
00773         
00774         domArticulated_systemRef articulated_system_motion = daeSafeCast<domArticulated_system>(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM));
00775         articulated_system_motion->setId(asmid.c_str());
00776         domMotionRef motion = daeSafeCast<domMotion>(articulated_system_motion->add(COLLADA_ELEMENT_MOTION));
00777         domMotion_techniqueRef mt = daeSafeCast<domMotion_technique>(motion->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00778         domInstance_articulated_systemRef ias_motion = daeSafeCast<domInstance_articulated_system>(motion->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM));
00779         ias_motion->setUrl(str(boost::format("#%s")%askid).c_str());
00780 
00781         
00782         domArticulated_systemRef articulated_system_kinematics = daeSafeCast<domArticulated_system>(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM));
00783         articulated_system_kinematics->setId(askid.c_str());
00784         domKinematicsRef kinematics = daeSafeCast<domKinematics>(articulated_system_kinematics->add(COLLADA_ELEMENT_KINEMATICS));
00785         domKinematics_techniqueRef kt = daeSafeCast<domKinematics_technique>(kinematics->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00786 
00787         _WriteInstance_kinematics_model(kinematics,askid,id);
00788 
00789         for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) {
00790             string axis_infosid = _ComputeId(str(boost::format("axis_info_inst%d")%idof));
00791             boost::shared_ptr<const urdf::Joint> pjoint = _ikmout->kmout->vaxissids.at(idof).pjoint;
00792             BOOST_ASSERT(_mapjointindices[pjoint] == (int)idof);
00793             
00794 
00795             
00796             domKinematics_axis_infoRef kai = daeSafeCast<domKinematics_axis_info>(kt->add(COLLADA_ELEMENT_AXIS_INFO));
00797             kai->setAxis(str(boost::format("%s/%s")%_ikmout->kmout->kmodel->getID()%_ikmout->kmout->vaxissids.at(idof).sid).c_str());
00798             kai->setSid(axis_infosid.c_str());
00799             bool bactive = !pjoint->mimic;
00800             double flower=0, fupper=0;
00801             if( pjoint->type != urdf::Joint::CONTINUOUS ) {
00802                 if( !!pjoint->limits ) {
00803                     flower = pjoint->limits->lower;
00804                     fupper = pjoint->limits->upper;
00805                 }
00806                 if( !!pjoint->safety ) {
00807                     flower = pjoint->safety->soft_lower_limit;
00808                     fupper = pjoint->safety->soft_upper_limit;
00809                 }
00810                 if( flower == fupper ) {
00811                     bactive = false;
00812                 }
00813                 double fmult = 1.0;
00814                 if( pjoint->type != urdf::Joint::PRISMATIC ) {
00815                     fmult = 180.0/M_PI;
00816                 }
00817                 domKinematics_limitsRef plimits = daeSafeCast<domKinematics_limits>(kai->add(COLLADA_ELEMENT_LIMITS));
00818                 daeSafeCast<domCommon_float_or_param::domFloat>(plimits->add(COLLADA_ELEMENT_MIN)->add(COLLADA_ELEMENT_FLOAT))->setValue(flower*fmult);
00819                 daeSafeCast<domCommon_float_or_param::domFloat>(plimits->add(COLLADA_ELEMENT_MAX)->add(COLLADA_ELEMENT_FLOAT))->setValue(fupper*fmult);
00820             }
00821 
00822             domCommon_bool_or_paramRef active = daeSafeCast<domCommon_bool_or_param>(kai->add(COLLADA_ELEMENT_ACTIVE));
00823             daeSafeCast<domCommon_bool_or_param::domBool>(active->add(COLLADA_ELEMENT_BOOL))->setValue(bactive);
00824             domCommon_bool_or_paramRef locked = daeSafeCast<domCommon_bool_or_param>(kai->add(COLLADA_ELEMENT_LOCKED));
00825             daeSafeCast<domCommon_bool_or_param::domBool>(locked->add(COLLADA_ELEMENT_BOOL))->setValue(false);
00826 
00827             
00828             domMotion_axis_infoRef mai = daeSafeCast<domMotion_axis_info>(mt->add(COLLADA_ELEMENT_AXIS_INFO));
00829             mai->setAxis(str(boost::format("%s/%s")%askid%axis_infosid).c_str());
00830             if( !!pjoint->limits ) {
00831                 domCommon_float_or_paramRef speed = daeSafeCast<domCommon_float_or_param>(mai->add(COLLADA_ELEMENT_SPEED));
00832                 daeSafeCast<domCommon_float_or_param::domFloat>(speed->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->velocity);
00833                 domCommon_float_or_paramRef accel = daeSafeCast<domCommon_float_or_param>(mai->add(COLLADA_ELEMENT_ACCELERATION));
00834                 daeSafeCast<domCommon_float_or_param::domFloat>(accel->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->effort);
00835             }
00836         }
00837 
00838         
00839         string asmsym = _ComputeId(str(boost::format("%s_%s")%asmid%_ikmout->ikm->getSid()));
00840         string assym = _ComputeId(str(boost::format("%s_%s")%_scene.kscene->getID()%_ikmout->ikm->getSid()));
00841         FOREACH(it, _ikmout->vkinematicsbindings) {
00842             domKinematics_newparamRef abm = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
00843             abm->setSid(asmsym.c_str());
00844             daeSafeCast<domKinematics_newparam::domSIDREF>(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%it->first).c_str());
00845             domKinematics_bindRef ab = daeSafeCast<domKinematics_bind>(ias->add(COLLADA_ELEMENT_BIND));
00846             ab->setSymbol(assym.c_str());
00847             daeSafeCast<domKinematics_param>(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s")%asmid%asmsym).c_str());
00848             _iasout->vkinematicsbindings.push_back(make_pair(string(ab->getSymbol()), it->second));
00849         }
00850         for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) {
00851             const axis_sids& kas = _ikmout->vaxissids.at(idof);
00852             domKinematics_newparamRef abm = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
00853             abm->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.axissid)).c_str());
00854             daeSafeCast<domKinematics_newparam::domSIDREF>(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.axissid).c_str());
00855             domKinematics_bindRef ab = daeSafeCast<domKinematics_bind>(ias->add(COLLADA_ELEMENT_BIND));
00856             ab->setSymbol(str(boost::format("%s_%s")%assym%kas.axissid).c_str());
00857             daeSafeCast<domKinematics_param>(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.axissid).c_str());
00858             string valuesid;
00859             if( kas.valuesid.size() > 0 ) {
00860                 domKinematics_newparamRef abmvalue = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
00861                 abmvalue->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.valuesid)).c_str());
00862                 daeSafeCast<domKinematics_newparam::domSIDREF>(abmvalue->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.valuesid).c_str());
00863                 domKinematics_bindRef abvalue = daeSafeCast<domKinematics_bind>(ias->add(COLLADA_ELEMENT_BIND));
00864                 valuesid = _ComputeId(str(boost::format("%s_%s")%assym%kas.valuesid));
00865                 abvalue->setSymbol(valuesid.c_str());
00866                 daeSafeCast<domKinematics_param>(abvalue->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.valuesid).c_str());
00867             }
00868             _iasout->vaxissids.push_back(axis_sids(ab->getSymbol(),valuesid,kas.jointnodesid));
00869         }
00870 
00871         boost::shared_ptr<instance_physics_model_output> ipmout = _WriteInstance_physics_model(id,_scene.pscene,_scene.pscene->getID(), _ikmout->kmout->_maplinkposes);
00872     }
00873 
00875     virtual void _WriteInstance_kinematics_model(daeElementRef parent, const string& sidscope, int id)
00876     {
00877         ROS_DEBUG_STREAM(str(boost::format("writing instance_kinematics_model %s\n")%_robot.getName()));
00878         boost::shared_ptr<kinematics_model_output> kmout = WriteKinematics_model(id);
00879 
00880         _ikmout.reset(new instance_kinematics_model_output());
00881         _ikmout->kmout = kmout;
00882         _ikmout->ikm = daeSafeCast<domInstance_kinematics_model>(parent->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_MODEL));
00883 
00884         string symscope, refscope;
00885         if( sidscope.size() > 0 ) {
00886             symscope = sidscope+string("_");
00887             refscope = sidscope+string("/");
00888         }
00889         string ikmsid = _ComputeId(str(boost::format("%s_inst")%kmout->kmodel->getID()));
00890         _ikmout->ikm->setUrl(str(boost::format("#%s")%kmout->kmodel->getID()).c_str());
00891         _ikmout->ikm->setSid(ikmsid.c_str());
00892 
00893         domKinematics_newparamRef kbind = daeSafeCast<domKinematics_newparam>(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
00894         kbind->setSid(_ComputeId(symscope+ikmsid).c_str());
00895         daeSafeCast<domKinematics_newparam::domSIDREF>(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid).c_str());
00896         _ikmout->vkinematicsbindings.push_back(make_pair(string(kbind->getSid()), str(boost::format("visual%d/node%d")%id%_maplinkindices[_robot.getRoot()])));
00897 
00898         _ikmout->vaxissids.reserve(kmout->vaxissids.size());
00899         int i = 0;
00900         FOREACH(it,kmout->vaxissids) {
00901             domKinematics_newparamRef kbind = daeSafeCast<domKinematics_newparam>(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
00902             string ref = it->sid;
00903             size_t index = ref.find("/");
00904             while(index != string::npos) {
00905                 ref[index] = '.';
00906                 index = ref.find("/",index+1);
00907             }
00908             string sid = _ComputeId(symscope+ikmsid+"_"+ref);
00909             kbind->setSid(sid.c_str());
00910             daeSafeCast<domKinematics_newparam::domSIDREF>(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid+"/"+it->sid).c_str());
00911             double value=0;
00912             double flower=0, fupper=0;
00913             if( !!it->pjoint->limits ) {
00914                 flower = it->pjoint->limits->lower;
00915                 fupper = it->pjoint->limits->upper;
00916             }
00917             if( flower > 0 || fupper < 0 ) {
00918                 value = 0.5*(flower+fupper);
00919             }
00920             domKinematics_newparamRef pvalueparam = daeSafeCast<domKinematics_newparam>(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
00921             pvalueparam->setSid((sid+string("_value")).c_str());
00922             daeSafeCast<domKinematics_newparam::domFloat>(pvalueparam->add(COLLADA_ELEMENT_FLOAT))->setValue(value);
00923             _ikmout->vaxissids.push_back(axis_sids(sid,pvalueparam->getSid(),kmout->vaxissids.at(i).jointnodesid));
00924             ++i;
00925         }
00926     }
00927 
00928     virtual boost::shared_ptr<kinematics_model_output> WriteKinematics_model(int id)
00929     {
00930         domKinematics_modelRef kmodel = daeSafeCast<domKinematics_model>(_kinematicsModelsLib->add(COLLADA_ELEMENT_KINEMATICS_MODEL));
00931         string kmodelid = _ComputeKinematics_modelId(id);
00932         kmodel->setId(kmodelid.c_str());
00933         kmodel->setName(_robot.getName().c_str());
00934 
00935         domKinematics_model_techniqueRef ktec = daeSafeCast<domKinematics_model_technique>(kmodel->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00936 
00937         
00938         domNodeRef pnoderoot = daeSafeCast<domNode>(_scene.vscene->add(COLLADA_ELEMENT_NODE));
00939         string bodyid = _ComputeId(str(boost::format("visual%d")%id));
00940         pnoderoot->setId(bodyid.c_str());
00941         pnoderoot->setSid(bodyid.c_str());
00942         pnoderoot->setName(_robot.getName().c_str());
00943 
00944         
00945         _mapjointindices.clear();
00946         int index=0;
00947         FOREACHC(itj, _robot.joints_) {
00948             _mapjointindices[itj->second] = index++;
00949         }
00950         _maplinkindices.clear();
00951         index=0;
00952         FOREACHC(itj, _robot.links_) {
00953             _maplinkindices[itj->second] = index++;
00954         }
00955         _mapmaterialindices.clear();
00956         index=0;
00957         FOREACHC(itj, _robot.materials_) {
00958             _mapmaterialindices[itj->second] = index++;
00959         }
00960 
00961         double lmin, lmax;
00962         vector<domJointRef> vdomjoints(_robot.joints_.size());
00963         boost::shared_ptr<kinematics_model_output> kmout(new kinematics_model_output());
00964         kmout->kmodel = kmodel;
00965         kmout->vaxissids.resize(_robot.joints_.size());
00966         kmout->vlinksids.resize(_robot.links_.size());
00967 
00968         FOREACHC(itjoint, _robot.joints_) {
00969             boost::shared_ptr<urdf::Joint> pjoint = itjoint->second;
00970             int index = _mapjointindices[itjoint->second];
00971             domJointRef pdomjoint = daeSafeCast<domJoint>(ktec->add(COLLADA_ELEMENT_JOINT));
00972             string jointid = _ComputeId(pjoint->name); 
00973             pdomjoint->setSid(jointid.c_str() );
00974             pdomjoint->setName(pjoint->name.c_str());
00975             domAxis_constraintRef axis;
00976             if( !!pjoint->limits ) {
00977                 lmin=pjoint->limits->lower;
00978                 lmax=pjoint->limits->upper;
00979             }
00980             else {
00981                 lmin = lmax = 0;
00982             }
00983 
00984             double fmult = 1.0;
00985             switch(pjoint->type) {
00986             case urdf::Joint::REVOLUTE:
00987             case urdf::Joint::CONTINUOUS:
00988                 axis = daeSafeCast<domAxis_constraint>(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE));
00989                 fmult = 180.0f/M_PI;
00990                 lmin*=fmult;
00991                 lmax*=fmult;
00992                 break;
00993             case urdf::Joint::PRISMATIC:
00994                 axis = daeSafeCast<domAxis_constraint>(pdomjoint->add(COLLADA_ELEMENT_PRISMATIC));
00995                 break;
00996             case urdf::Joint::FIXED:
00997                 axis = daeSafeCast<domAxis_constraint>(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE));
00998                 lmin = 0;
00999                 lmax = 0;
01000                 fmult = 0;
01001                 break;
01002             default:
01003                 ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type));
01004                 break;
01005             }
01006 
01007             if( !axis ) {
01008                 continue;
01009             }
01010 
01011             int ia = 0;
01012             string axisid = _ComputeId(str(boost::format("axis%d")%ia));
01013             axis->setSid(axisid.c_str());
01014             kmout->vaxissids.at(index).pjoint = pjoint;
01015             kmout->vaxissids.at(index).sid = jointid+string("/")+axisid;
01016             kmout->vaxissids.at(index).iaxis = ia;
01017             domAxisRef paxis = daeSafeCast<domAxis>(axis->add(COLLADA_ELEMENT_AXIS));
01018             paxis->getValue().setCount(3);
01019             paxis->getValue()[0] = pjoint->axis.x;
01020             paxis->getValue()[1] = pjoint->axis.y;
01021             paxis->getValue()[2] = pjoint->axis.z;
01022             if( pjoint->type != urdf::Joint::CONTINUOUS ) {
01023                 domJoint_limitsRef plimits = daeSafeCast<domJoint_limits>(axis->add(COLLADA_TYPE_LIMITS));
01024                 daeSafeCast<domMinmax>(plimits->add(COLLADA_ELEMENT_MIN))->getValue() = lmin;
01025                 daeSafeCast<domMinmax>(plimits->add(COLLADA_ELEMENT_MAX))->getValue() = lmax;
01026             }
01027             vdomjoints.at(index) = pdomjoint;
01028         }
01029 
01030         LINKOUTPUT childinfo = _WriteLink(_robot.getRoot(), ktec, pnoderoot, kmodel->getID());
01031         FOREACHC(itused, childinfo.listusedlinks) {
01032             kmout->vlinksids.at(itused->first) = itused->second;
01033         }
01034         FOREACH(itprocessed,childinfo.listprocesseddofs) {
01035             kmout->vaxissids.at(itprocessed->first).jointnodesid = itprocessed->second;
01036         }
01037         kmout->_maplinkposes = childinfo._maplinkposes;
01038 
01039         
01040         FOREACHC(itjoint, _robot.joints_) {
01041             string jointsid = _ComputeId(itjoint->second->name);
01042             boost::shared_ptr<urdf::Joint> pjoint = itjoint->second;
01043             if( !pjoint->mimic ) {
01044                 continue;
01045             }
01046 
01047             domFormulaRef pf = daeSafeCast<domFormula>(ktec->add(COLLADA_ELEMENT_FORMULA));
01048             string formulaid = _ComputeId(str(boost::format("%s_formula")%jointsid));
01049             pf->setSid(formulaid.c_str());
01050             domCommon_float_or_paramRef ptarget = daeSafeCast<domCommon_float_or_param>(pf->add(COLLADA_ELEMENT_TARGET));
01051             string targetjointid = str(boost::format("%s/%s")%kmodel->getID()%jointsid);
01052             daeSafeCast<domCommon_param>(ptarget->add(COLLADA_TYPE_PARAM))->setValue(targetjointid.c_str());
01053 
01054             domTechniqueRef pftec = daeSafeCast<domTechnique>(pf->add(COLLADA_ELEMENT_TECHNIQUE));
01055             pftec->setProfile("OpenRAVE");
01056             
01057             {
01058                 daeElementRef poselt = pftec->add("equation");
01059                 poselt->setAttribute("type","position");
01060                 
01061                 
01062                 daeElementRef pmath_math = poselt->add("math");
01063                 daeElementRef pmath_apply = pmath_math->add("apply");
01064                 {
01065                     daeElementRef pmath_plus = pmath_apply->add("plus");
01066                     daeElementRef pmath_apply1 = pmath_apply->add("apply");
01067                     {
01068                         daeElementRef pmath_times = pmath_apply1->add("times");
01069                         daeElementRef pmath_const0 = pmath_apply1->add("cn");
01070                         pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier));
01071                         daeElementRef pmath_symb = pmath_apply1->add("csymbol");
01072                         pmath_symb->setAttribute("encoding","COLLADA");
01073                         pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)));
01074                     }
01075                     daeElementRef pmath_const1 = pmath_apply->add("cn");
01076                     pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset));
01077                 }
01078             }
01079             
01080             {
01081                 daeElementRef derivelt = pftec->add("equation");
01082                 derivelt->setAttribute("type","first_partial");
01083                 derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str());
01084                 daeElementRef pmath_const0 = derivelt->add("cn");
01085                 pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier));
01086             }
01087             
01088             {
01089                 daeElementRef derivelt = pftec->add("equation");
01090                 derivelt->setAttribute("type","second_partial");
01091                 derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str());
01092                 daeElementRef pmath_const0 = derivelt->add("cn");
01093                 pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier));
01094             }
01095 
01096             {
01097                 domFormula_techniqueRef pfcommontec = daeSafeCast<domFormula_technique>(pf->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01098                 
01099                 
01100                 daeElementRef pmath_math = pfcommontec->add("math");
01101                 daeElementRef pmath_apply = pmath_math->add("apply");
01102                 {
01103                     daeElementRef pmath_plus = pmath_apply->add("plus");
01104                     daeElementRef pmath_apply1 = pmath_apply->add("apply");
01105                     {
01106                         daeElementRef pmath_times = pmath_apply1->add("times");
01107                         daeElementRef pmath_const0 = pmath_apply1->add("cn");
01108                         pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier));
01109                         daeElementRef pmath_symb = pmath_apply1->add("csymbol");
01110                         pmath_symb->setAttribute("encoding","COLLADA");
01111                         pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)));
01112                     }
01113                     daeElementRef pmath_const1 = pmath_apply->add("cn");
01114                     pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset));
01115                 }
01116             }
01117         }
01118 
01119         return kmout;
01120     }
01121 
01128     virtual LINKOUTPUT _WriteLink(boost::shared_ptr<const urdf::Link> plink, daeElementRef pkinparent, domNodeRef pnodeparent, const string& strModelUri)
01129     {
01130         LINKOUTPUT out;
01131         int linkindex = _maplinkindices[plink];
01132         string linksid = _ComputeId(plink->name);
01133         domLinkRef pdomlink = daeSafeCast<domLink>(pkinparent->add(COLLADA_ELEMENT_LINK));
01134         pdomlink->setName(plink->name.c_str());
01135         pdomlink->setSid(linksid.c_str());
01136 
01137         domNodeRef pnode = daeSafeCast<domNode>(pnodeparent->add(COLLADA_ELEMENT_NODE));
01138         string nodeid = _ComputeId(str(boost::format("v%s_node%d")%strModelUri%linkindex));
01139         pnode->setId( nodeid.c_str() );
01140         string nodesid = _ComputeId(str(boost::format("node%d")%linkindex));
01141         pnode->setSid(nodesid.c_str());
01142         pnode->setName(plink->name.c_str());
01143 
01144         boost::shared_ptr<urdf::Geometry> geometry;
01145         boost::shared_ptr<urdf::Material> material;
01146         urdf::Pose geometry_origin;
01147         if( !!plink->visual ) {
01148             geometry = plink->visual->geometry;
01149             material = plink->visual->material;
01150             geometry_origin = plink->visual->origin;
01151         }
01152         else if( !!plink->collision ) {
01153             geometry = plink->collision->geometry;
01154             geometry_origin = plink->collision->origin;
01155         }
01156 
01157         urdf::Pose geometry_origin_inv = _poseInverse(geometry_origin);
01158 
01159         if( !!geometry ) {
01160             bool write_visual = false;
01161             if ( !!plink->visual ) {
01162               if (plink->visual_groups.size() > 0) {
01163                 std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<urdf::Visual > > > >::const_iterator def_group
01164                   = plink->visual_groups.find("default");
01165                 if (def_group != plink->visual_groups.end()) {
01166                   if (def_group->second->size() > 1) {
01167                     int igeom = 0;
01168                     for (std::vector<boost::shared_ptr<urdf::Visual > >::const_iterator it = def_group->second->begin();
01169                          it != def_group->second->end(); it++) {
01170                       
01171                       string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom));
01172                       igeom++;
01173                       domGeometryRef pdomgeom;
01174                       if ( it != def_group->second->begin() ) {
01175                         urdf::Pose org_trans =  _poseMult(geometry_origin_inv, (*it)->origin);
01176                         pdomgeom = _WriteGeometry((*it)->geometry, geomid, &org_trans);
01177                       } else {
01178                         pdomgeom = _WriteGeometry((*it)->geometry, geomid);
01179                       }
01180                       domInstance_geometryRef pinstgeom = daeSafeCast<domInstance_geometry>(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
01181                       pinstgeom->setUrl((string("#") + geomid).c_str());
01182                       
01183                       _WriteMaterial(pdomgeom->getID(), (*it)->material);
01184                       domBind_materialRef pmat = daeSafeCast<domBind_material>(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL));
01185                       domBind_material::domTechnique_commonRef pmattec = daeSafeCast<domBind_material::domTechnique_common>(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01186                       domInstance_materialRef pinstmat = daeSafeCast<domInstance_material>(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL));
01187                       pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat")));
01188                       pinstmat->setSymbol("mat0");
01189                       write_visual = true;
01190                     }
01191                   }
01192                 }
01193               }
01194             }
01195             if (!write_visual) {
01196               
01197               int igeom = 0;
01198               string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom));
01199               domGeometryRef pdomgeom = _WriteGeometry(geometry, geomid);
01200               domInstance_geometryRef pinstgeom = daeSafeCast<domInstance_geometry>(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
01201               pinstgeom->setUrl((string("#")+geomid).c_str());
01202 
01203               
01204               _WriteMaterial(pdomgeom->getID(), material);
01205               domBind_materialRef pmat = daeSafeCast<domBind_material>(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL));
01206               domBind_material::domTechnique_commonRef pmattec = daeSafeCast<domBind_material::domTechnique_common>(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01207               domInstance_materialRef pinstmat = daeSafeCast<domInstance_material>(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL));
01208               pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat")));
01209               pinstmat->setSymbol("mat0");
01210             }
01211         }
01212 
01213         _WriteTransformation(pnode, geometry_origin);
01214 
01215         
01216         FOREACHC(itjoint, plink->child_joints) {
01217             boost::shared_ptr<urdf::Joint> pjoint = *itjoint;
01218             int index = _mapjointindices[pjoint];
01219 
01220             
01221             domLink::domAttachment_fullRef attachment_full = daeSafeCast<domLink::domAttachment_full>(pdomlink->add(COLLADA_ELEMENT_ATTACHMENT_FULL));
01222             string jointid = str(boost::format("%s/%s")%strModelUri%_ComputeId(pjoint->name));
01223             attachment_full->setJoint(jointid.c_str());
01224 
01225             LINKOUTPUT childinfo = _WriteLink(_robot.getLink(pjoint->child_link_name), attachment_full, pnode, strModelUri);
01226             FOREACH(itused,childinfo.listusedlinks) {
01227                 out.listusedlinks.push_back(make_pair(itused->first,linksid+string("/")+itused->second));
01228             }
01229             FOREACH(itprocessed,childinfo.listprocesseddofs) {
01230                 out.listprocesseddofs.push_back(make_pair(itprocessed->first,nodesid+string("/")+itprocessed->second));
01231             }
01232             FOREACH(itlinkpos,childinfo._maplinkposes) {
01233                 out._maplinkposes[itlinkpos->first] = _poseMult(pjoint->parent_to_joint_origin_transform,itlinkpos->second);
01234             }
01235             
01236             string jointnodesid = _ComputeId(str(boost::format("node_%s_axis0")%pjoint->name));
01237             switch(pjoint->type) {
01238             case urdf::Joint::REVOLUTE:
01239             case urdf::Joint::CONTINUOUS:
01240             case urdf::Joint::FIXED: {
01241                 domRotateRef protate = daeSafeCast<domRotate>(childinfo.pnode->add(COLLADA_ELEMENT_ROTATE,0));
01242                 protate->setSid(jointnodesid.c_str());
01243                 protate->getValue().setCount(4);
01244                 protate->getValue()[0] = pjoint->axis.x;
01245                 protate->getValue()[1] = pjoint->axis.y;
01246                 protate->getValue()[2] = pjoint->axis.z;
01247                 protate->getValue()[3] = 0;
01248                 break;
01249             }
01250             case urdf::Joint::PRISMATIC: {
01251                 domTranslateRef ptrans = daeSafeCast<domTranslate>(childinfo.pnode->add(COLLADA_ELEMENT_TRANSLATE,0));
01252                 ptrans->setSid(jointnodesid.c_str());
01253                 ptrans->getValue().setCount(3);
01254                 ptrans->getValue()[0] = 0;
01255                 ptrans->getValue()[1] = 0;
01256                 ptrans->getValue()[2] = 0;
01257                 break;
01258             }
01259             default:
01260                 ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type));
01261                 break;
01262             }
01263 
01264             _WriteTransformation(attachment_full, pjoint->parent_to_joint_origin_transform);
01265             _WriteTransformation(childinfo.pnode, pjoint->parent_to_joint_origin_transform);
01266             _WriteTransformation(childinfo.pnode, geometry_origin_inv); 
01267             out.listprocesseddofs.push_back(make_pair(index,string(childinfo.pnode->getSid())+string("/")+jointnodesid));
01268             
01269         }
01270 
01271         out._maplinkposes[plink] = urdf::Pose();
01272         out.listusedlinks.push_back(make_pair(linkindex,linksid));
01273         out.plink = pdomlink;
01274         out.pnode = pnode;
01275         return out;
01276     }
01277 
01278     domGeometryRef _WriteGeometry(boost::shared_ptr<urdf::Geometry> geometry, const std::string& geometry_id, urdf::Pose *org_trans = NULL)
01279     {
01280         domGeometryRef cgeometry = daeSafeCast<domGeometry>(_geometriesLib->add(COLLADA_ELEMENT_GEOMETRY));
01281         cgeometry->setId(geometry_id.c_str());
01282         switch (geometry->type) {
01283         case urdf::Geometry::MESH: {
01284             urdf::Mesh* urdf_mesh = (urdf::Mesh*) geometry.get();
01285             cgeometry->setName(urdf_mesh->filename.c_str());
01286             _loadMesh(urdf_mesh->filename, cgeometry, urdf_mesh->scale, org_trans);
01287             break;
01288         }
01289         case urdf::Geometry::SPHERE: {
01290             shapes::Sphere sphere(static_cast<urdf::Sphere*>(geometry.get())->radius);
01291             boost::scoped_ptr<shapes::Mesh> mesh(shapes::createMeshFromShape(sphere));
01292             _loadVertices(mesh.get(), cgeometry);
01293             break;
01294         }
01295         case urdf::Geometry::BOX: {
01296             shapes::Box box(static_cast<urdf::Box*>(geometry.get())->dim.x / 2.0,
01297                             static_cast<urdf::Box*>(geometry.get())->dim.y / 2.0,
01298                             static_cast<urdf::Box*>(geometry.get())->dim.z / 2.0);
01299             boost::scoped_ptr<shapes::Mesh> mesh(shapes::createMeshFromShape(box));
01300             _loadVertices(mesh.get(), cgeometry);
01301             break;
01302         }
01303         case urdf::Geometry::CYLINDER: {
01304             shapes::Cylinder cyl(static_cast<urdf::Cylinder*>(geometry.get())->radius,
01305                                  static_cast<urdf::Cylinder*>(geometry.get())->length);
01306             boost::scoped_ptr<shapes::Mesh> mesh(shapes::createMeshFromShape(cyl));
01307             _loadVertices(mesh.get(), cgeometry);
01308             break;
01309         }
01310         default: {
01311             throw ColladaUrdfException(str(boost::format("undefined geometry type %d, name %s")%(int)geometry->type%geometry_id));
01312         }
01313         }
01314         return cgeometry;
01315     }
01316 
01317     void _WriteMaterial(const string& geometry_id, boost::shared_ptr<urdf::Material> material)
01318     {
01319         string effid = geometry_id+string("_eff");
01320         string matid = geometry_id+string("_mat");
01321         domMaterialRef pdommat = daeSafeCast<domMaterial>(_materialsLib->add(COLLADA_ELEMENT_MATERIAL));
01322         pdommat->setId(matid.c_str());
01323         domInstance_effectRef pdominsteff = daeSafeCast<domInstance_effect>(pdommat->add(COLLADA_ELEMENT_INSTANCE_EFFECT));
01324         pdominsteff->setUrl((string("#")+effid).c_str());
01325 
01326         urdf::Color ambient, diffuse;
01327         ambient.init("0.1 0.1 0.1 0");
01328         diffuse.init("1 1 1 0");
01329 
01330         if( !!material ) {
01331             ambient.r = diffuse.r = material->color.r;
01332             ambient.g = diffuse.g = material->color.g;
01333             ambient.b = diffuse.b = material->color.b;
01334             ambient.a = diffuse.a = material->color.a;
01335         }
01336 
01337         domEffectRef effect = _WriteEffect(geometry_id, ambient, diffuse);
01338 
01339         
01340         domMaterialRef dommaterial = daeSafeCast<domMaterial>(_materialsLib->add(COLLADA_ELEMENT_MATERIAL));
01341         string material_id = geometry_id + string("_mat");
01342         dommaterial->setId(material_id.c_str());
01343         {
01344             
01345             domInstance_effectRef instance_effect = daeSafeCast<domInstance_effect>(dommaterial->add(COLLADA_ELEMENT_INSTANCE_EFFECT));
01346             string effect_id(effect->getId());
01347             instance_effect->setUrl((string("#") + effect_id).c_str());
01348         }
01349         
01350 
01351         domEffectRef pdomeff = _WriteEffect(effid, ambient, diffuse);
01352     }
01353 
01354     boost::shared_ptr<instance_physics_model_output> _WriteInstance_physics_model(int id, daeElementRef parent, const string& sidscope, const MAPLINKPOSES& maplinkposes)
01355     {
01356         boost::shared_ptr<physics_model_output> pmout = WritePhysics_model(id, maplinkposes);
01357         boost::shared_ptr<instance_physics_model_output> ipmout(new instance_physics_model_output());
01358         ipmout->pmout = pmout;
01359         ipmout->ipm = daeSafeCast<domInstance_physics_model>(parent->add(COLLADA_ELEMENT_INSTANCE_PHYSICS_MODEL));
01360         string bodyid = _ComputeId(str(boost::format("visual%d")%id));
01361         ipmout->ipm->setParent(xsAnyURI(*ipmout->ipm,string("#")+bodyid));
01362         string symscope, refscope;
01363         if( sidscope.size() > 0 ) {
01364             symscope = sidscope+string("_");
01365             refscope = sidscope+string("/");
01366         }
01367         string ipmsid = str(boost::format("%s_inst")%pmout->pmodel->getID());
01368         ipmout->ipm->setUrl(str(boost::format("#%s")%pmout->pmodel->getID()).c_str());
01369         ipmout->ipm->setSid(ipmsid.c_str());
01370 
01371         string kmodelid = _ComputeKinematics_modelId(id);
01372         for(size_t i = 0; i < pmout->vrigidbodysids.size(); ++i) {
01373             domInstance_rigid_bodyRef pirb = daeSafeCast<domInstance_rigid_body>(ipmout->ipm->add(COLLADA_ELEMENT_INSTANCE_RIGID_BODY));
01374             pirb->setBody(pmout->vrigidbodysids[i].c_str());
01375             pirb->setTarget(xsAnyURI(*pirb,str(boost::format("#v%s_node%d")%kmodelid%i)));
01376         }
01377 
01378         return ipmout;
01379     }
01380 
01381     boost::shared_ptr<physics_model_output> WritePhysics_model(int id, const MAPLINKPOSES& maplinkposes)
01382     {
01383         boost::shared_ptr<physics_model_output> pmout(new physics_model_output());
01384         pmout->pmodel = daeSafeCast<domPhysics_model>(_physicsModelsLib->add(COLLADA_ELEMENT_PHYSICS_MODEL));
01385         string pmodelid = str(boost::format("pmodel%d")%id);
01386         pmout->pmodel->setId(pmodelid.c_str());
01387         pmout->pmodel->setName(_robot.getName().c_str());
01388         FOREACHC(itlink,_robot.links_) {
01389             domRigid_bodyRef rigid_body = daeSafeCast<domRigid_body>(pmout->pmodel->add(COLLADA_ELEMENT_RIGID_BODY));
01390             string rigidsid = str(boost::format("rigid%d")%_maplinkindices[itlink->second]);
01391             pmout->vrigidbodysids.push_back(rigidsid);
01392             rigid_body->setSid(rigidsid.c_str());
01393             rigid_body->setName(itlink->second->name.c_str());
01394             domRigid_body::domTechnique_commonRef ptec = daeSafeCast<domRigid_body::domTechnique_common>(rigid_body->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01395             boost::shared_ptr<urdf::Inertial> inertial = itlink->second->inertial;
01396             if( !!inertial ) {
01397                 daeSafeCast<domRigid_body::domTechnique_common::domDynamic>(ptec->add(COLLADA_ELEMENT_DYNAMIC))->setValue(xsBoolean(true)); 
01398                 domTargetable_floatRef mass = daeSafeCast<domTargetable_float>(ptec->add(COLLADA_ELEMENT_MASS));
01399                 mass->setValue(inertial->mass);
01400                 double fCovariance[9] = { inertial->ixx, inertial->ixy, inertial->ixz, inertial->ixy, inertial->iyy, inertial->iyz, inertial->ixz, inertial->iyz, inertial->izz};
01401                 double eigenvalues[3], eigenvectors[9];
01402                 mathextra::EigenSymmetric3(fCovariance,eigenvalues,eigenvectors);
01403                 boost::array<double,12> minertiaframe;
01404                 for(int j = 0; j < 3; ++j) {
01405                     minertiaframe[4*0+j] = eigenvectors[3*j];
01406                     minertiaframe[4*1+j] = eigenvectors[3*j+1];
01407                     minertiaframe[4*2+j] = eigenvectors[3*j+2];
01408                 }
01409                 urdf::Pose tinertiaframe;
01410                 tinertiaframe.rotation = _quatFromMatrix(minertiaframe);
01411                 tinertiaframe = _poseMult(inertial->origin,tinertiaframe);
01412 
01413                 domTargetable_float3Ref pinertia = daeSafeCast<domTargetable_float3>(ptec->add(COLLADA_ELEMENT_INERTIA));
01414                 pinertia->getValue().setCount(3);
01415                 pinertia->getValue()[0] = eigenvalues[0];
01416                 pinertia->getValue()[1] = eigenvalues[1];
01417                 pinertia->getValue()[2] = eigenvalues[2];
01418                 urdf::Pose posemassframe = _poseMult(maplinkposes.find(itlink->second)->second,tinertiaframe);
01419                 _WriteTransformation(ptec->add(COLLADA_ELEMENT_MASS_FRAME), posemassframe);
01420 
01421                 
01422                 
01423                 
01424                 
01425                 
01426                 
01427                 
01428                 
01429                 
01430                 
01431             }
01432         }
01433         return pmout;
01434     }
01435 
01436     void _loadVertices(const shapes::Mesh *mesh, domGeometryRef pdomgeom) {
01437         
01438         
01439         std::vector<char> buffer;
01440         shapes::writeSTLBinary(mesh, buffer);
01441         
01442         
01443         Assimp::Importer importer;
01444         
01445         
01446         const aiScene* scene = importer.ReadFileFromMemory(reinterpret_cast<const void*>(&buffer[0]), buffer.size(),
01447                                                            aiProcess_Triangulate            |
01448                                                            aiProcess_JoinIdenticalVertices  |
01449                                                            aiProcess_SortByPType            |
01450                                                            aiProcess_OptimizeGraph          |
01451                                                            aiProcess_OptimizeMeshes, "stl");
01452         
01453         
01454 
01455             domMeshRef pdommesh = daeSafeCast<domMesh>(pdomgeom->add(COLLADA_ELEMENT_MESH));
01456             domSourceRef pvertsource = daeSafeCast<domSource>(pdommesh->add(COLLADA_ELEMENT_SOURCE));
01457             domAccessorRef pacc;
01458             domFloat_arrayRef parray;
01459             {
01460                 pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str());
01461 
01462                 parray = daeSafeCast<domFloat_array>(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY));
01463                 parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str());
01464                 parray->setDigits(6); 
01465 
01466                 domSource::domTechnique_commonRef psourcetec = daeSafeCast<domSource::domTechnique_common>(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01467                 pacc = daeSafeCast<domAccessor>(psourcetec->add(COLLADA_ELEMENT_ACCESSOR));
01468                 pacc->setSource(xsAnyURI(*parray, std::string("#")+string(parray->getID())));
01469                 pacc->setStride(3);
01470 
01471                 domParamRef px = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01472                 px->setName("X"); px->setType("float");
01473                 domParamRef py = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01474                 py->setName("Y"); py->setType("float");
01475                 domParamRef pz = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01476                 pz->setName("Z"); pz->setType("float");
01477             }
01478             domVerticesRef pverts = daeSafeCast<domVertices>(pdommesh->add(COLLADA_ELEMENT_VERTICES));
01479             {
01480                 pverts->setId("vertices");
01481                 domInput_localRef pvertinput = daeSafeCast<domInput_local>(pverts->add(COLLADA_ELEMENT_INPUT));
01482                 pvertinput->setSemantic("POSITION");
01483                 pvertinput->setSource(domUrifragment(*pvertsource, std::string("#")+std::string(pvertsource->getID())));
01484             }
01485             _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(), urdf::Vector3(1,1,1));
01486             pacc->setCount(parray->getCount());
01487     }
01488 
01489     void _loadMesh(std::string const& filename, domGeometryRef pdomgeom, const urdf::Vector3& scale, urdf::Pose *org_trans)
01490     {
01491         const aiScene* scene = _importer.ReadFile(filename, aiProcess_SortByPType|aiProcess_Triangulate); 
01492         if( !scene ) {
01493             ROS_WARN("failed to load resource %s",filename.c_str());
01494             return;
01495         }
01496         if( !scene->mRootNode ) {
01497             ROS_WARN("resource %s has no data",filename.c_str());
01498             return;
01499         }
01500         if (!scene->HasMeshes()) {
01501             ROS_WARN_STREAM(str(boost::format("No meshes found in file %s")%filename));
01502             return;
01503         }
01504         domMeshRef pdommesh = daeSafeCast<domMesh>(pdomgeom->add(COLLADA_ELEMENT_MESH));
01505         domSourceRef pvertsource = daeSafeCast<domSource>(pdommesh->add(COLLADA_ELEMENT_SOURCE));
01506         domAccessorRef pacc;
01507         domFloat_arrayRef parray;
01508         {
01509             pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str());
01510 
01511             parray = daeSafeCast<domFloat_array>(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY));
01512             parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str());
01513             parray->setDigits(6); 
01514 
01515             domSource::domTechnique_commonRef psourcetec = daeSafeCast<domSource::domTechnique_common>(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
01516             pacc = daeSafeCast<domAccessor>(psourcetec->add(COLLADA_ELEMENT_ACCESSOR));
01517             pacc->setSource(xsAnyURI(*parray, string("#")+string(parray->getID())));
01518             pacc->setStride(3);
01519 
01520             domParamRef px = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01521             px->setName("X"); px->setType("float");
01522             domParamRef py = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01523             py->setName("Y"); py->setType("float");
01524             domParamRef pz = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
01525             pz->setName("Z"); pz->setType("float");
01526         }
01527         domVerticesRef pverts = daeSafeCast<domVertices>(pdommesh->add(COLLADA_ELEMENT_VERTICES));
01528         {
01529             pverts->setId("vertices");
01530             domInput_localRef pvertinput = daeSafeCast<domInput_local>(pverts->add(COLLADA_ELEMENT_INPUT));
01531             pvertinput->setSemantic("POSITION");
01532             pvertinput->setSource(domUrifragment(*pvertsource, string("#")+string(pvertsource->getID())));
01533         }
01534         _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(),scale,org_trans);
01535         pacc->setCount(parray->getCount());
01536     }
01537 
01538     void _buildAiMesh(const aiScene* scene, aiNode* node, domMeshRef pdommesh, domFloat_arrayRef parray, const string& geomid, const urdf::Vector3& scale, urdf::Pose *org_trans = NULL)
01539     {
01540         if( !node ) {
01541             return;
01542         }
01543         aiMatrix4x4 transform = node->mTransformation;
01544         aiNode *pnode = node->mParent;
01545         while (pnode) {
01546             
01547             
01548             if (pnode->mParent != NULL) {
01549                 transform = pnode->mTransformation * transform;
01550             }
01551             pnode = pnode->mParent;
01552         }
01553 
01554         {
01555             uint32_t vertexOffset = parray->getCount();
01556             uint32_t nTotalVertices=0;
01557             for (uint32_t i = 0; i < node->mNumMeshes; i++) {
01558                 aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
01559                 nTotalVertices += input_mesh->mNumVertices;
01560             }
01561 
01562             parray->getValue().grow(parray->getCount()+nTotalVertices*3);
01563             parray->setCount(parray->getCount()+nTotalVertices);
01564 
01565             for (uint32_t i = 0; i < node->mNumMeshes; i++) {
01566                 aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
01567                 for (uint32_t j = 0; j < input_mesh->mNumVertices; j++) {
01568                     aiVector3D p = input_mesh->mVertices[j];
01569                     p *= transform;
01570                     if (org_trans) {
01571                       urdf::Vector3 vv;
01572                       vv.x = p.x*scale.x;
01573                       vv.y = p.y*scale.y;
01574                       vv.z = p.z*scale.z;
01575                       urdf::Vector3 nv = _poseMult(*org_trans, vv);
01576                       parray->getValue().append(nv.x);
01577                       parray->getValue().append(nv.y);
01578                       parray->getValue().append(nv.z);
01579                     } else {
01580                       parray->getValue().append(p.x*scale.x);
01581                       parray->getValue().append(p.y*scale.y);
01582                       parray->getValue().append(p.z*scale.z);
01583                     }
01584                 }
01585             }
01586 
01587             
01588 
01589             vector<int> triangleindices, otherindices;
01590             int nNumOtherPrimitives = 0;
01591             for (uint32_t i = 0; i < node->mNumMeshes; i++) {
01592                 aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
01593                 uint32_t indexCount = 0, otherIndexCount = 0;
01594                 for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) {
01595                     aiFace& face = input_mesh->mFaces[j];
01596                     if( face.mNumIndices == 3 ) {
01597                         indexCount += face.mNumIndices;
01598                     }
01599                     else {
01600                         otherIndexCount += face.mNumIndices;
01601                     }
01602                 }
01603                 triangleindices.reserve(triangleindices.size()+indexCount);
01604                 otherindices.reserve(otherindices.size()+otherIndexCount);
01605                 for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) {
01606                     aiFace& face = input_mesh->mFaces[j];
01607                     if( face.mNumIndices == 3 ) {
01608                         triangleindices.push_back(vertexOffset+face.mIndices[0]);
01609                         triangleindices.push_back(vertexOffset+face.mIndices[1]);
01610                         triangleindices.push_back(vertexOffset+face.mIndices[2]);
01611                     }
01612                     else {
01613                         for (uint32_t k = 0; k < face.mNumIndices; ++k) {
01614                             otherindices.push_back(face.mIndices[k]+vertexOffset);
01615                         }
01616                         nNumOtherPrimitives++;
01617                     }
01618                 }
01619                 vertexOffset += input_mesh->mNumVertices;
01620             }
01621 
01622             if( triangleindices.size() > 0 ) {
01623                 domTrianglesRef ptris = daeSafeCast<domTriangles>(pdommesh->add(COLLADA_ELEMENT_TRIANGLES));
01624                 ptris->setCount(triangleindices.size()/3);
01625                 ptris->setMaterial("mat0");
01626                 domInput_local_offsetRef pvertoffset = daeSafeCast<domInput_local_offset>(ptris->add(COLLADA_ELEMENT_INPUT));
01627                 pvertoffset->setSemantic("VERTEX");
01628                 pvertoffset->setOffset(0);
01629                 pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid)));
01630                 domPRef pindices = daeSafeCast<domP>(ptris->add(COLLADA_ELEMENT_P));
01631                 pindices->getValue().setCount(triangleindices.size());
01632                 for(size_t ind = 0; ind < triangleindices.size(); ++ind) {
01633                     pindices->getValue()[ind] = triangleindices[ind];
01634                 }
01635             }
01636 
01637             if( nNumOtherPrimitives > 0 ) {
01638                 domPolylistRef ptris = daeSafeCast<domPolylist>(pdommesh->add(COLLADA_ELEMENT_POLYLIST));
01639                 ptris->setCount(nNumOtherPrimitives);
01640                 ptris->setMaterial("mat0");
01641                 domInput_local_offsetRef pvertoffset = daeSafeCast<domInput_local_offset>(ptris->add(COLLADA_ELEMENT_INPUT));
01642                 pvertoffset->setSemantic("VERTEX");
01643                 pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid)));
01644                 domPRef pindices = daeSafeCast<domP>(ptris->add(COLLADA_ELEMENT_P));
01645                 pindices->getValue().setCount(otherindices.size());
01646                 for(size_t ind = 0; ind < otherindices.size(); ++ind) {
01647                     pindices->getValue()[ind] = otherindices[ind];
01648                 }
01649 
01650                 domPolylist::domVcountRef pcount = daeSafeCast<domPolylist::domVcount>(ptris->add(COLLADA_ELEMENT_VCOUNT));
01651                 pcount->getValue().setCount(nNumOtherPrimitives);
01652                 uint32_t offset = 0;
01653                 for (uint32_t i = 0; i < node->mNumMeshes; i++) {
01654                     aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
01655                     for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) {
01656                         aiFace& face = input_mesh->mFaces[j];
01657                         if( face.mNumIndices > 3 ) {
01658                             pcount->getValue()[offset++] = face.mNumIndices;
01659                         }
01660                     }
01661                 }
01662             }
01663         }
01664 
01665         for (uint32_t i=0; i < node->mNumChildren; ++i) {
01666             _buildAiMesh(scene, node->mChildren[i], pdommesh,parray,geomid,scale,org_trans);
01667         }
01668     }
01669 
01670 
01671     domEffectRef _WriteEffect(std::string const& effect_id, urdf::Color const& color_ambient, urdf::Color const& color_diffuse)
01672     {
01673         
01674         domEffectRef effect = daeSafeCast<domEffect>(_effectsLib->add(COLLADA_ELEMENT_EFFECT));
01675         effect->setId(effect_id.c_str());
01676         {
01677             
01678             domProfile_commonRef profile = daeSafeCast<domProfile_common>(effect->add(COLLADA_ELEMENT_PROFILE_COMMON));
01679             {
01680                 
01681                 domProfile_common::domTechniqueRef technique = daeSafeCast<domProfile_common::domTechnique>(profile->add(COLLADA_ELEMENT_TECHNIQUE));
01682                 {
01683                     
01684                     domProfile_common::domTechnique::domPhongRef phong = daeSafeCast<domProfile_common::domTechnique::domPhong>(technique->add(COLLADA_ELEMENT_PHONG));
01685                     {
01686                         
01687                         domFx_common_color_or_textureRef ambient = daeSafeCast<domFx_common_color_or_texture>(phong->add(COLLADA_ELEMENT_AMBIENT));
01688                         {
01689                             
01690                             domFx_common_color_or_texture::domColorRef ambient_color = daeSafeCast<domFx_common_color_or_texture::domColor>(ambient->add(COLLADA_ELEMENT_COLOR));
01691                             ambient_color->getValue().setCount(4);
01692                             ambient_color->getValue()[0] = color_ambient.r;
01693                             ambient_color->getValue()[1] = color_ambient.g;
01694                             ambient_color->getValue()[2] = color_ambient.b;
01695                             ambient_color->getValue()[3] = color_ambient.a;
01696                             
01697                         }
01698                         
01699 
01700                         
01701                         domFx_common_color_or_textureRef diffuse = daeSafeCast<domFx_common_color_or_texture>(phong->add(COLLADA_ELEMENT_DIFFUSE));
01702                         {
01703                             
01704                             domFx_common_color_or_texture::domColorRef diffuse_color = daeSafeCast<domFx_common_color_or_texture::domColor>(diffuse->add(COLLADA_ELEMENT_COLOR));
01705                             diffuse_color->getValue().setCount(4);
01706                             diffuse_color->getValue()[0] = color_diffuse.r;
01707                             diffuse_color->getValue()[1] = color_diffuse.g;
01708                             diffuse_color->getValue()[2] = color_diffuse.b;
01709                             diffuse_color->getValue()[3] = color_diffuse.a;
01710                             
01711                         }
01712                         
01713                     }
01714                     
01715                 }
01716                 
01717             }
01718             
01719         }
01720         
01721 
01722         return effect;
01723     }
01724 
01728     void _WriteTransformation(daeElementRef pelt, const urdf::Pose& t)
01729     {
01730         domRotateRef prot = daeSafeCast<domRotate>(pelt->add(COLLADA_ELEMENT_ROTATE,0));
01731         domTranslateRef ptrans = daeSafeCast<domTranslate>(pelt->add(COLLADA_ELEMENT_TRANSLATE,0));
01732         ptrans->getValue().setCount(3);
01733         ptrans->getValue()[0] = t.position.x;
01734         ptrans->getValue()[1] = t.position.y;
01735         ptrans->getValue()[2] = t.position.z;
01736 
01737         prot->getValue().setCount(4);
01738         
01739         double sinang = t.rotation.x*t.rotation.x+t.rotation.y*t.rotation.y+t.rotation.z*t.rotation.z;
01740         if( std::fabs(sinang) < 1e-10 ) {
01741             prot->getValue()[0] = 1;
01742             prot->getValue()[1] = 0;
01743             prot->getValue()[2] = 0;
01744             prot->getValue()[3] = 0;
01745         }
01746         else {
01747             urdf::Rotation quat;
01748             if( t.rotation.w < 0 ) {
01749                 quat.x = -t.rotation.x;
01750                 quat.y = -t.rotation.y;
01751                 quat.z = -t.rotation.z;
01752                 quat.w = -t.rotation.w;
01753             }
01754             else {
01755                 quat = t.rotation;
01756             }
01757             sinang = std::sqrt(sinang);
01758             prot->getValue()[0] = quat.x/sinang;
01759             prot->getValue()[1] = quat.y/sinang;
01760             prot->getValue()[2] = quat.z/sinang;
01761             prot->getValue()[3] = angles::to_degrees(2.0*std::atan2(sinang,quat.w));
01762         }
01763     }
01764 
01765     
01766     void _WriteBindingsInstance_kinematics_scene()
01767     {
01768         FOREACHC(it, _iasout->vkinematicsbindings) {
01769             domBind_kinematics_modelRef pmodelbind = daeSafeCast<domBind_kinematics_model>(_scene.kiscene->add(COLLADA_ELEMENT_BIND_KINEMATICS_MODEL));
01770             pmodelbind->setNode(it->second.c_str());
01771             daeSafeCast<domCommon_param>(pmodelbind->add(COLLADA_ELEMENT_PARAM))->setValue(it->first.c_str());
01772         }
01773         FOREACHC(it, _iasout->vaxissids) {
01774             domBind_joint_axisRef pjointbind = daeSafeCast<domBind_joint_axis>(_scene.kiscene->add(COLLADA_ELEMENT_BIND_JOINT_AXIS));
01775             pjointbind->setTarget(it->jointnodesid.c_str());
01776             daeSafeCast<domCommon_param>(pjointbind->add(COLLADA_ELEMENT_AXIS)->add(COLLADA_TYPE_PARAM))->setValue(it->axissid.c_str());
01777             daeSafeCast<domCommon_param>(pjointbind->add(COLLADA_ELEMENT_VALUE)->add(COLLADA_TYPE_PARAM))->setValue(it->valuesid.c_str());
01778         }
01779     }
01780 
01781 private:
01782     static urdf::Vector3 _poseMult(const urdf::Pose& p, const urdf::Vector3& v)
01783     {
01784         double ww = 2 * p.rotation.x * p.rotation.x;
01785         double wx = 2 * p.rotation.x * p.rotation.y;
01786         double wy = 2 * p.rotation.x * p.rotation.z;
01787         double wz = 2 * p.rotation.x * p.rotation.w;
01788         double xx = 2 * p.rotation.y * p.rotation.y;
01789         double xy = 2 * p.rotation.y * p.rotation.z;
01790         double xz = 2 * p.rotation.y * p.rotation.w;
01791         double yy = 2 * p.rotation.z * p.rotation.z;
01792         double yz = 2 * p.rotation.z * p.rotation.w;
01793         urdf::Vector3 vnew;
01794         vnew.x = (1-xx-yy) * v.x + (wx-yz) * v.y + (wy+xz)*v.z + p.position.x;
01795         vnew.y = (wx+yz) * v.x + (1-ww-yy) * v.y + (xy-wz)*v.z + p.position.y;
01796         vnew.z = (wy-xz) * v.x + (xy+wz) * v.y + (1-ww-xx)*v.z + p.position.z;
01797         return vnew;
01798     }
01799 
01800     static urdf::Pose _poseInverse(const urdf::Pose& p)
01801     {
01802         urdf::Pose pinv;
01803         pinv.rotation.x = -p.rotation.x;
01804         pinv.rotation.y = -p.rotation.y;
01805         pinv.rotation.z = -p.rotation.z;
01806         pinv.rotation.w = p.rotation.w;
01807         urdf::Vector3 t = _poseMult(pinv,p.position);
01808         pinv.position.x = -t.x;
01809         pinv.position.y = -t.y;
01810         pinv.position.z = -t.z;
01811         return pinv;
01812     }
01813 
01814     static urdf::Rotation _quatMult(const urdf::Rotation& quat0, const urdf::Rotation& quat1)
01815     {
01816         urdf::Rotation q;
01817         q.x = quat0.w*quat1.x + quat0.x*quat1.w + quat0.y*quat1.z - quat0.z*quat1.y;
01818         q.y = quat0.w*quat1.y + quat0.y*quat1.w + quat0.z*quat1.x - quat0.x*quat1.z;
01819         q.z = quat0.w*quat1.z + quat0.z*quat1.w + quat0.x*quat1.y - quat0.y*quat1.x;
01820         q.w = quat0.w*quat1.w - quat0.x*quat1.x - quat0.y*quat1.y - quat0.z*quat1.z;
01821         double fnorm = std::sqrt(q.x*q.x+q.y*q.y+q.z*q.z+q.w*q.w);
01822         
01823         q.x /= fnorm;
01824         q.y /= fnorm;
01825         q.z /= fnorm;
01826         q.w /= fnorm;
01827         return q;
01828     }
01829 
01830     static urdf::Pose _poseMult(const urdf::Pose& p0, const urdf::Pose& p1)
01831     {
01832         urdf::Pose p;
01833         p.position = _poseMult(p0,p1.position);
01834         p.rotation = _quatMult(p0.rotation,p1.rotation);
01835         return p;
01836     }
01837 
01838     static urdf::Rotation _quatFromMatrix(const boost::array<double,12>& mat)
01839     {
01840         urdf::Rotation rot;
01841         double tr = mat[4*0+0] + mat[4*1+1] + mat[4*2+2];
01842         if (tr >= 0) {
01843             rot.w = tr + 1;
01844             rot.x = (mat[4*2+1] - mat[4*1+2]);
01845             rot.y = (mat[4*0+2] - mat[4*2+0]);
01846             rot.z = (mat[4*1+0] - mat[4*0+1]);
01847         }
01848         else {
01849             
01850             if (mat[4*1+1] > mat[4*0+0]) {
01851                 if (mat[4*2+2] > mat[4*1+1]) {
01852                     rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1;
01853                     rot.x = (mat[4*2+0] + mat[4*0+2]);
01854                     rot.y = (mat[4*1+2] + mat[4*2+1]);
01855                     rot.w = (mat[4*1+0] - mat[4*0+1]);
01856                 }
01857                 else {
01858                     rot.y = (mat[4*1+1] - (mat[4*2+2] + mat[4*0+0])) + 1;
01859                     rot.z = (mat[4*1+2] + mat[4*2+1]);
01860                     rot.x = (mat[4*0+1] + mat[4*1+0]);
01861                     rot.w = (mat[4*0+2] - mat[4*2+0]);
01862                 }
01863             }
01864             else if (mat[4*2+2] > mat[4*0+0]) {
01865                 rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1;
01866                 rot.x = (mat[4*2+0] + mat[4*0+2]);
01867                 rot.y = (mat[4*1+2] + mat[4*2+1]);
01868                 rot.w = (mat[4*1+0] - mat[4*0+1]);
01869             }
01870             else {
01871                 rot.x = (mat[4*0+0] - (mat[4*1+1] + mat[4*2+2])) + 1;
01872                 rot.y = (mat[4*0+1] + mat[4*1+0]);
01873                 rot.z = (mat[4*2+0] + mat[4*0+2]);
01874                 rot.w = (mat[4*2+1] - mat[4*1+2]);
01875             }
01876         }
01877         double fnorm = std::sqrt(rot.x*rot.x+rot.y*rot.y+rot.z*rot.z+rot.w*rot.w);
01878         
01879         rot.x /= fnorm;
01880         rot.y /= fnorm;
01881         rot.z /= fnorm;
01882         rot.w /= fnorm;
01883         return rot;
01884     }
01885 
01886     static std::string _ComputeKinematics_modelId(int id)
01887     {
01888         return _ComputeId(str(boost::format("kmodel%d")%id));
01889     }
01890 
01892     static std::string _ComputeId(const std::string& name)
01893     {
01894         std::string newname = name;
01895         for(size_t i = 0; i < newname.size(); ++i) {
01896             if( newname[i] == '/' || newname[i] == ' ' || newname[i] == '.' ) {
01897                 newname[i] = '_';
01898             }
01899         }
01900         return newname;
01901     }
01902 
01903     int _writeoptions;
01904 
01905     const urdf::Model& _robot;
01906     DAE _collada;
01907     domCOLLADA* _dom;
01908     daeDocument *_doc;
01909     domCOLLADA::domSceneRef _globalscene;
01910 
01911     domLibrary_visual_scenesRef _visualScenesLib;
01912     domLibrary_kinematics_scenesRef _kinematicsScenesLib;
01913     domLibrary_kinematics_modelsRef _kinematicsModelsLib;
01914     domLibrary_articulated_systemsRef _articulatedSystemsLib;
01915     domLibrary_physics_scenesRef _physicsScenesLib;
01916     domLibrary_physics_modelsRef _physicsModelsLib;
01917     domLibrary_materialsRef _materialsLib;
01918     domLibrary_effectsRef _effectsLib;
01919     domLibrary_geometriesRef _geometriesLib;
01920     domTechniqueRef _sensorsLib; 
01921     SCENE _scene;
01922 
01923     boost::shared_ptr<instance_kinematics_model_output> _ikmout;
01924     boost::shared_ptr<instance_articulated_system_output> _iasout;
01925     std::map< boost::shared_ptr<const urdf::Joint>, int > _mapjointindices;
01926     std::map< boost::shared_ptr<const urdf::Link>, int > _maplinkindices;
01927     std::map< boost::shared_ptr<const urdf::Material>, int > _mapmaterialindices;
01928     Assimp::Importer _importer;
01929 };
01930 
01931 
01932 ColladaUrdfException::ColladaUrdfException(std::string const& what)
01933     : std::runtime_error(what)
01934 {
01935 }
01936 
01937 bool WriteUrdfModelToColladaFile(urdf::Model const& robot_model, string const& file) {
01938     ColladaWriter writer(robot_model,0);
01939     if ( ! writer.convert() ) {
01940         std::cerr << std::endl << "Error converting document" << std::endl;
01941         return -1;
01942     }
01943     return writer.writeTo(file);
01944 }
01945 
01946 }