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