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


collada_urdf
Author(s): Tim Field, Rosen Diankov
autogenerated on Mon Oct 6 2014 04:13:47