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 #include "collada_urdf/collada_writer.h"
00038
00039 #include "collada_urdf/stl_loader.h"
00040
00041 #include <boost/date_time/posix_time/posix_time.hpp>
00042 #include <boost/date_time/posix_time/posix_time_io.hpp>
00043 #include <boost/foreach.hpp>
00044
00045 #define foreach BOOST_FOREACH
00046
00047 using std::string;
00048 using std::map;
00049 using std::vector;
00050 using boost::shared_ptr;
00051
00052 namespace collada_urdf {
00053
00054 int ColladaWriter::s_doc_count_ = 0;
00055
00056 ColladaWriter::ColladaWriter(urdf::Model const& robot) : robot_(robot), dom_(NULL) {
00057 daeErrorHandler::setErrorHandler(this);
00058
00059 collada_.reset(new DAE);
00060 collada_->setIOPlugin(NULL);
00061 collada_->setDatabase(NULL);
00062 }
00063
00064 ColladaWriter::~ColladaWriter() { }
00065
00066 shared_ptr<DAE> ColladaWriter::convert() {
00067 try {
00068 string doc_count_str = boost::lexical_cast<string>(s_doc_count_++);
00069 initDocument(string("collada_urdf_") + doc_count_str + string(".dae"));
00070
00071 SCENE scene = createScene();
00072
00073 setupPhysics(scene);
00074 addGeometries();
00075 addKinematics(scene);
00076 addVisuals(scene);
00077 addMaterials();
00078 addBindings(scene);
00079
00080 return collada_;
00081 }
00082 catch (ColladaUrdfException ex) {
00083 ROS_ERROR("Error converting: %s", ex.what());
00084 return shared_ptr<DAE>();
00085 }
00086 }
00087
00088
00089
00090 void ColladaWriter::handleError(daeString msg) {
00091 throw ColladaUrdfException(msg);
00092 }
00093
00094 void ColladaWriter::handleWarning(daeString msg) {
00095 std::cerr << "COLLADA DOM warning: " << msg << std::endl;
00096 }
00097
00098 void ColladaWriter::initDocument(string const& documentName) {
00099
00100 daeDocument* doc = NULL;
00101 daeInt error = collada_->getDatabase()->insertDocument(documentName.c_str(), &doc);
00102 if (error != DAE_OK || doc == NULL)
00103 throw ColladaUrdfException("Failed to create document");
00104
00105 dom_ = daeSafeCast<domCOLLADA>(doc->getDomRoot());
00106 dom_->setAttribute("xmlns:math", "http://www.w3.org/1998/Math/MathML");
00107
00108
00109 domAssetRef asset = daeSafeCast<domAsset>(dom_->add(COLLADA_ELEMENT_ASSET));
00110 {
00111 string date = getTimeStampString();
00112
00113 domAsset::domCreatedRef created = daeSafeCast<domAsset::domCreated>(asset->add(COLLADA_ELEMENT_CREATED));
00114 created->setValue(date.c_str());
00115 domAsset::domModifiedRef modified = daeSafeCast<domAsset::domModified>(asset->add(COLLADA_ELEMENT_MODIFIED));
00116 modified->setValue(date.c_str());
00117
00118 domAsset::domContributorRef contrib = daeSafeCast<domAsset::domContributor>(asset->add(COLLADA_ELEMENT_CONTRIBUTOR));
00119
00120 domAsset::domContributor::domAuthoring_toolRef authoringtool = daeSafeCast<domAsset::domContributor::domAuthoring_tool>(contrib->add(COLLADA_ELEMENT_AUTHORING_TOOL));
00121 authoringtool->setValue("URDF Collada Writer");
00122
00123 domAsset::domUnitRef units = daeSafeCast<domAsset::domUnit>(asset->add(COLLADA_ELEMENT_UNIT));
00124 units->setMeter(1);
00125 units->setName("meter");
00126
00127 domAsset::domUp_axisRef zup = daeSafeCast<domAsset::domUp_axis>(asset->add(COLLADA_ELEMENT_UP_AXIS));
00128 zup->setValue(UP_AXIS_Z_UP);
00129 }
00130
00131
00132 scene_ = daeSafeCast<domCOLLADA::domScene>(dom_->add(COLLADA_ELEMENT_SCENE));
00133 visualScenesLib_ = daeSafeCast<domLibrary_visual_scenes>(dom_->add(COLLADA_ELEMENT_LIBRARY_VISUAL_SCENES));
00134 visualScenesLib_->setId("vscenes");
00135 geometriesLib_ = daeSafeCast<domLibrary_geometries>(dom_->add(COLLADA_ELEMENT_LIBRARY_GEOMETRIES));
00136 geometriesLib_->setId("geometries");
00137 kinematicsScenesLib_ = daeSafeCast<domLibrary_kinematics_scenes>(dom_->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_SCENES));
00138 kinematicsScenesLib_->setId("kscenes");
00139 kinematicsModelsLib_ = daeSafeCast<domLibrary_kinematics_models>(dom_->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_MODELS));
00140 kinematicsModelsLib_->setId("kmodels");
00141 jointsLib_ = daeSafeCast<domLibrary_joints>(dom_->add(COLLADA_ELEMENT_LIBRARY_JOINTS));
00142 jointsLib_->setId("joints");
00143 physicsScenesLib_ = daeSafeCast<domLibrary_physics_scenes>(dom_->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_SCENES));
00144 physicsScenesLib_->setId("physics_scenes");
00145 effectsLib_ = daeSafeCast<domLibrary_effects>(dom_->add(COLLADA_ELEMENT_LIBRARY_EFFECTS));
00146 effectsLib_->setId("effects");
00147 materialsLib_ = daeSafeCast<domLibrary_materials>(dom_->add(COLLADA_ELEMENT_LIBRARY_MATERIALS));
00148 materialsLib_->setId("materials");
00149 }
00150
00151 ColladaWriter::SCENE ColladaWriter::createScene() {
00152 SCENE s;
00153
00154
00155 s.vscene = daeSafeCast<domVisual_scene>(visualScenesLib_->add(COLLADA_ELEMENT_VISUAL_SCENE));
00156 s.vscene->setId("vscene");
00157 s.vscene->setName("URDF Visual Scene");
00158
00159
00160 s.viscene = daeSafeCast<domInstance_with_extra>(scene_->add(COLLADA_ELEMENT_INSTANCE_VISUAL_SCENE));
00161 s.viscene->setUrl((string("#") + string(s.vscene->getID())).c_str());
00162
00163
00164 s.kscene = daeSafeCast<domKinematics_scene>(kinematicsScenesLib_->add(COLLADA_ELEMENT_KINEMATICS_SCENE));
00165 s.kscene->setId("kscene");
00166 s.kscene->setName("URDF Kinematics Scene");
00167
00168
00169 s.kiscene = daeSafeCast<domInstance_kinematics_scene>(scene_->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_SCENE));
00170 s.kiscene->setUrl((string("#") + string(s.kscene->getID())).c_str());
00171
00172
00173 s.pscene = daeSafeCast<domPhysics_scene>(physicsScenesLib_->add(COLLADA_ELEMENT_PHYSICS_SCENE));
00174 s.pscene->setId("pscene");
00175 s.pscene->setName("URDF Physics Scene");
00176
00177
00178 s.piscene = daeSafeCast<domInstance_with_extra>(scene_->add(COLLADA_ELEMENT_INSTANCE_PHYSICS_SCENE));
00179 s.piscene->setUrl((string("#") + string(s.pscene->getID())).c_str());
00180
00181 return s;
00182 }
00183
00184 void ColladaWriter::setupPhysics(SCENE const& scene) {
00185
00186 domPhysics_scene::domTechnique_commonRef common = daeSafeCast<domPhysics_scene::domTechnique_common>(scene.pscene->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00187 {
00188
00189 domTargetable_float3Ref g = daeSafeCast<domTargetable_float3>(common->add(COLLADA_ELEMENT_GRAVITY));
00190 g->getValue().set3(0.0, 0.0, 0.0);
00191
00192 }
00193
00194 }
00195
00196 void ColladaWriter::addGeometries() {
00197 int link_num = 0;
00198
00199 for (map<string, shared_ptr<urdf::Link> >::const_iterator i = robot_.links_.begin(); i != robot_.links_.end(); i++) {
00200 shared_ptr<urdf::Link> urdf_link = i->second;
00201 boost::shared_ptr< urdf::Geometry > geometry;
00202 if( !!urdf_link->visual ) {
00203 geometry = urdf_link->visual->geometry;
00204 }
00205 else if (!!urdf_link->collision ) {
00206 geometry = urdf_link->collision->geometry;
00207 }
00208 if( !geometry ) {
00209 continue;
00210 }
00211 switch (geometry->type) {
00212 case urdf::Geometry::MESH: {
00213 urdf::Mesh* urdf_mesh = (urdf::Mesh*) geometry.get();
00214
00215 string filename = urdf_mesh->filename;
00216 urdf::Vector3 scale = urdf_mesh->scale;
00217
00218
00219 domGeometryRef geometry = daeSafeCast<domGeometry>(geometriesLib_->add(COLLADA_ELEMENT_GEOMETRY));
00220 string geometry_id = string("g1.link") + boost::lexical_cast<string>(link_num) + string(".geom0");
00221 geometry->setId(geometry_id.c_str());
00222 {
00223 loadMesh(filename, geometry, geometry_id);
00224 }
00225 geometry_ids_[urdf_link->name] = geometry_id;
00226
00227
00228 link_num++;
00229 break;
00230 }
00231 case urdf::Geometry::SPHERE: {
00232 std::cerr << "Warning: geometry type SPHERE of link " << urdf_link->name << " not exported" << std::endl;
00233 break;
00234 }
00235 case urdf::Geometry::BOX: {
00236 std::cerr << "Warning: geometry type BOX of link " << urdf_link->name << " not exported" << std::endl;
00237 break;
00238 }
00239 case urdf::Geometry::CYLINDER: {
00240 std::cerr << "Warning: geometry type CYLINDER of link " << urdf_link->name << " not exported" << std::endl;
00241 break;
00242 }
00243 default: {
00244 std::cerr << "Warning: geometry type " << geometry->type << " of link " << urdf_link->name << " not exported" << std::endl;
00245 break;
00246 }
00247 }
00248 }
00249 }
00250
00251 void ColladaWriter::loadMesh(string const& filename, domGeometryRef geometry, string const& geometry_id) {
00252
00253 resource_retriever::MemoryResource resource;
00254 resource_retriever::Retriever retriever;
00255 try {
00256 resource = retriever.get(filename.c_str());
00257 }
00258 catch (resource_retriever::Exception& e) {
00259 std::cerr << "Unable to load mesh file " << filename << ": " << e.what() << std::endl;
00260 return;
00261 }
00262
00263
00264 try {
00265 loadMeshWithSTLLoader(resource, geometry, geometry_id);
00266 }
00267 catch (ColladaUrdfException e) {
00268 std::cerr << "Unable to load mesh file " << filename << ": " << e.what() << std::endl;
00269 }
00270 }
00271
00272 bool ColladaWriter::loadMeshWithSTLLoader(resource_retriever::MemoryResource const& resource, domGeometryRef geometry, string const& geometry_id) {
00273
00274 char tmp_filename[] = "/tmp/collada_urdf_XXXXXX";
00275 int fd = mkstemp(tmp_filename);
00276 if (fd == -1)
00277 throw ColladaUrdfException("Couldn't create temporary file");
00278
00279 if ((uint32_t) write(fd, resource.data.get(), resource.size) != resource.size) {
00280 close(fd);
00281 unlink(tmp_filename);
00282 throw ColladaUrdfException("Couldn't write resource to file");
00283 }
00284 close(fd);
00285
00286
00287 STLLoader loader;
00288 shared_ptr<Mesh> stl_mesh = loader.load(string(tmp_filename));
00289 if (stl_mesh == shared_ptr<Mesh>()) {
00290 unlink(tmp_filename);
00291 throw ColladaUrdfException("Couldn't import STL mesh");
00292 }
00293
00294
00295 buildMeshFromSTLLoader(stl_mesh, geometry, geometry_id);
00296
00297
00298 unlink(tmp_filename);
00299
00300 return true;
00301 }
00302
00303 void ColladaWriter::buildMeshFromSTLLoader(shared_ptr<Mesh> stl_mesh, daeElementRef parent, string const& geometry_id) {
00304
00305 domMeshRef mesh = daeSafeCast<domMesh>(parent->add(COLLADA_ELEMENT_MESH));
00306 {
00307 unsigned int num_vertices = stl_mesh->vertices.size();
00308 unsigned int num_indices = stl_mesh->indices.size();
00309 unsigned int num_faces = num_indices / 3;
00310
00311
00312 domSourceRef positions_source = daeSafeCast<domSource>(mesh->add(COLLADA_ELEMENT_SOURCE));
00313 positions_source->setId((geometry_id + string(".positions")).c_str());
00314 {
00315
00316 domFloat_arrayRef positions_array = daeSafeCast<domFloat_array>(positions_source->add(COLLADA_ELEMENT_FLOAT_ARRAY));
00317 positions_array->setId((geometry_id + string(".positions-array")).c_str());
00318 positions_array->setCount(num_vertices * 3);
00319 positions_array->setDigits(6);
00320 positions_array->getValue().setCount(num_vertices * 3);
00321 for (unsigned int j = 0; j < num_vertices; j++) {
00322 positions_array->getValue()[j * 3 ] = stl_mesh->vertices[j].x;
00323 positions_array->getValue()[j * 3 + 1] = stl_mesh->vertices[j].y;
00324 positions_array->getValue()[j * 3 + 2] = stl_mesh->vertices[j].z;
00325 }
00326
00327
00328
00329 domSource::domTechnique_commonRef source_tech = daeSafeCast<domSource::domTechnique_common>(positions_source->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00330 {
00331
00332 domAccessorRef accessor = daeSafeCast<domAccessor>(source_tech->add(COLLADA_ELEMENT_ACCESSOR));
00333 accessor->setCount(num_vertices / 3);
00334 accessor->setSource(xsAnyURI(*positions_array, string("#") + geometry_id + string(".positions-array")));
00335 accessor->setStride(3);
00336 {
00337
00338
00339
00340 domParamRef px = daeSafeCast<domParam>(accessor->add(COLLADA_ELEMENT_PARAM)); px->setName("X"); px->setType("float");
00341 domParamRef py = daeSafeCast<domParam>(accessor->add(COLLADA_ELEMENT_PARAM)); py->setName("Y"); py->setType("float");
00342 domParamRef pz = daeSafeCast<domParam>(accessor->add(COLLADA_ELEMENT_PARAM)); pz->setName("Z"); pz->setType("float");
00343 }
00344
00345 }
00346
00347 }
00348
00349
00350 domVerticesRef vertices = daeSafeCast<domVertices>(mesh->add(COLLADA_ELEMENT_VERTICES));
00351 string vertices_id = geometry_id + string(".vertices");
00352 vertices->setId(vertices_id.c_str());
00353 {
00354
00355 domInput_localRef vertices_input = daeSafeCast<domInput_local>(vertices->add(COLLADA_ELEMENT_INPUT));
00356 vertices_input->setSemantic("POSITION");
00357 vertices_input->setSource(domUrifragment(*positions_source, string("#") + string(positions_source->getId())));
00358 }
00359
00360
00361
00362 domTrianglesRef triangles = daeSafeCast<domTriangles>(mesh->add(COLLADA_ELEMENT_TRIANGLES));
00363 triangles->setCount(num_faces);
00364 triangles->setMaterial("mat0");
00365 {
00366
00367 domInput_local_offsetRef vertex_offset = daeSafeCast<domInput_local_offset>(triangles->add(COLLADA_ELEMENT_INPUT));
00368 vertex_offset->setSemantic("VERTEX");
00369 vertex_offset->setOffset(0);
00370 vertex_offset->setSource(domUrifragment(*positions_source, string("#") + vertices_id));
00371 {
00372
00373 domPRef indices = daeSafeCast<domP>(triangles->add(COLLADA_ELEMENT_P));
00374 indices->getValue().setCount(num_indices);
00375 for (unsigned int i = 0; i < num_indices; i++)
00376 indices->getValue()[i] = stl_mesh->indices[i];
00377
00378 }
00379 }
00380
00381 }
00382
00383 }
00384
00385 void ColladaWriter::addJoints(daeElementRef parent) {
00386 int joint_num = 0;
00387 for (map<string, shared_ptr<urdf::Joint> >::const_iterator i = robot_.joints_.begin(); i != robot_.joints_.end(); i++) {
00388 shared_ptr<urdf::Joint> urdf_joint = i->second;
00389
00390
00391 domJointRef joint = daeSafeCast<domJoint>(parent->add(COLLADA_ELEMENT_JOINT));
00392 string joint_sid = string("joint") + boost::lexical_cast<string>(joint_num);
00393 joint_num++;
00394 joint->setName(urdf_joint->name.c_str());
00395 joint->setSid(joint_sid.c_str());
00396 joint_sids_[urdf_joint->name] = joint_sid;
00397
00398 double axis_x = urdf_joint->axis.x;
00399 double axis_y = urdf_joint->axis.y;
00400 double axis_z = urdf_joint->axis.z;
00401 if (axis_x == 0.0 && axis_y == 0.0 && axis_z == 0.0) {
00402 axis_x = 1.0;
00403 axis_y = 0.0;
00404 axis_z = 0.0;
00405 }
00406
00407 switch (urdf_joint->type)
00408 {
00409 case urdf::Joint::REVOLUTE: {
00410
00411 domAxis_constraintRef revolute = daeSafeCast<domAxis_constraint>(joint->add(COLLADA_ELEMENT_REVOLUTE));
00412 revolute->setSid("axis0");
00413 {
00414
00415 domAxisRef axis = daeSafeCast<domAxis>(revolute->add(COLLADA_ELEMENT_AXIS));
00416 {
00417 axis->getValue().setCount(3);
00418 axis->getValue()[0] = axis_x;
00419 axis->getValue()[1] = axis_y;
00420 axis->getValue()[2] = axis_z;
00421 }
00422
00423
00424
00425 domJoint_limitsRef limits = daeSafeCast<domJoint_limits>(revolute->add(COLLADA_ELEMENT_LIMITS));
00426 {
00427 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MIN))->getValue() = angles::to_degrees(urdf_joint->limits->lower);
00428 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MAX))->getValue() = angles::to_degrees(urdf_joint->limits->upper);
00429 }
00430
00431 }
00432
00433 break;
00434 }
00435 case urdf::Joint::CONTINUOUS: {
00436
00437
00438
00439 domAxis_constraintRef revolute = daeSafeCast<domAxis_constraint>(joint->add(COLLADA_ELEMENT_REVOLUTE));
00440 revolute->setSid("axis0");
00441 {
00442
00443 domAxisRef axis = daeSafeCast<domAxis>(revolute->add(COLLADA_ELEMENT_AXIS));
00444 {
00445 axis->getValue().setCount(3);
00446 axis->getValue()[0] = axis_x;
00447 axis->getValue()[1] = axis_y;
00448 axis->getValue()[2] = axis_z;
00449 }
00450
00451 }
00452
00453 break;
00454 }
00455 case urdf::Joint::PRISMATIC: {
00456
00457 domAxis_constraintRef prismatic = daeSafeCast<domAxis_constraint>(joint->add(COLLADA_ELEMENT_PRISMATIC));
00458 prismatic->setSid("axis0");
00459 {
00460
00461 domAxisRef axis = daeSafeCast<domAxis>(prismatic->add(COLLADA_ELEMENT_AXIS));
00462 {
00463 axis->getValue().setCount(3);
00464 axis->getValue()[0] = axis_x;
00465 axis->getValue()[1] = axis_y;
00466 axis->getValue()[2] = axis_z;
00467 }
00468
00469
00470
00471 domJoint_limitsRef limits = daeSafeCast<domJoint_limits>(prismatic->add(COLLADA_ELEMENT_LIMITS));
00472 {
00473 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MIN))->getValue() = urdf_joint->limits->lower;
00474 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MAX))->getValue() = urdf_joint->limits->upper;
00475 }
00476
00477 }
00478
00479 break;
00480 }
00481 case urdf::Joint::FIXED: {
00482
00483
00484 domAxis_constraintRef revolute = daeSafeCast<domAxis_constraint>(joint->add(COLLADA_ELEMENT_REVOLUTE));
00485 revolute->setSid("axis0");
00486 {
00487
00488 domAxisRef axis = daeSafeCast<domAxis>(revolute->add(COLLADA_ELEMENT_AXIS));
00489 {
00490 axis->getValue().setCount(3);
00491 axis->getValue()[0] = axis_x;
00492 axis->getValue()[1] = axis_y;
00493 axis->getValue()[2] = axis_z;
00494 }
00495
00496
00497
00498 domJoint_limitsRef limits = daeSafeCast<domJoint_limits>(revolute->add(COLLADA_ELEMENT_LIMITS));
00499 {
00500 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MIN))->getValue() = 0.0;
00501 daeSafeCast<domMinmax>(limits->add(COLLADA_ELEMENT_MAX))->getValue() = 0.0;
00502 }
00503
00504 }
00505
00506 break;
00507 }
00508 case urdf::Joint::UNKNOWN: {
00509 std::cerr << "Joint type UNKNOWN of joint " << urdf_joint->name << " is unsupported" << std::endl;
00510 break;
00511 }
00512 case urdf::Joint::FLOATING: {
00513 std::cerr << "Joint type FLOATING of joint " << urdf_joint->name << " is unsupported" << std::endl;
00514 break;
00515 }
00516 case urdf::Joint::PLANAR: {
00517 std::cerr << "Joint type PLANAR of joint " << urdf_joint->name << " is unsupported" << std::endl;
00518 break;
00519 }
00520 default: {
00521 std::cerr << "Joint type " << urdf_joint->type << " of joint " << urdf_joint->name << " is unsupported" << std::endl;
00522 break;
00523 }
00524 }
00525 }
00526 }
00527
00528 void ColladaWriter::addBindings(SCENE const& scene) {
00529 string model_id = kmodel_->getID();
00530 string inst_model_sid = string("inst_") + model_id;
00531
00532
00533
00534 domBind_kinematics_modelRef kmodel_bind = daeSafeCast<domBind_kinematics_model>(scene.kiscene->add(COLLADA_ELEMENT_BIND_KINEMATICS_MODEL));
00535 kmodel_bind->setNode("v1.node0");
00536 daeSafeCast<domCommon_param>(kmodel_bind->add(COLLADA_ELEMENT_PARAM))->setValue(string(string(scene.kscene->getID()) + string(".") + inst_model_sid).c_str());
00537
00538 for (map<string, shared_ptr<urdf::Joint> >::const_iterator i = robot_.joints_.begin(); i != robot_.joints_.end(); i++) {
00539 shared_ptr<urdf::Joint> urdf_joint = i->second;
00540
00541 int idof = 0;
00542 string joint_sid = joint_sids_[urdf_joint->name];
00543 string axis_name = string("axis") + boost::lexical_cast<string>(idof);
00544 string joint_axis_sid = string("kscene.inst_") + model_id + string(".") + joint_sid + string(".") + axis_name;
00545 string joint_axis_value_sid = joint_axis_sid + string("_value");
00546
00547
00548 domBind_joint_axisRef joint_bind = daeSafeCast<domBind_joint_axis>(scene.kiscene->add(COLLADA_ELEMENT_BIND_JOINT_AXIS));
00549 string node_name = node_ids_[urdf_joint->name];
00550 joint_bind->setTarget((node_name + string("/node_") + joint_sid + string("_") + axis_name).c_str());
00551 {
00552
00553 domCommon_sidref_or_paramRef axis_bind = daeSafeCast<domCommon_sidref_or_param>(joint_bind->add(COLLADA_ELEMENT_AXIS));
00554 {
00555 daeSafeCast<domCommon_param>(axis_bind->add(COLLADA_ELEMENT_PARAM))->setValue(joint_axis_sid.c_str());
00556 }
00557
00558
00559 domCommon_float_or_paramRef value_bind = daeSafeCast<domCommon_float_or_param>(joint_bind->add(COLLADA_ELEMENT_VALUE));
00560 {
00561 daeSafeCast<domCommon_param>(value_bind->add(COLLADA_ELEMENT_PARAM))->setValue(joint_axis_value_sid.c_str());
00562 }
00563 }
00564
00565 }
00566 }
00567
00568 void ColladaWriter::addKinematics(SCENE const& scene) {
00569
00570 domKinematics_modelRef kmodel = daeSafeCast<domKinematics_model>(kinematicsModelsLib_->add(COLLADA_ELEMENT_KINEMATICS_MODEL));
00571 kmodel->setId("k1");
00572 kmodel->setName(robot_.getName().c_str());
00573 {
00574
00575 domKinematics_model_techniqueRef technique = daeSafeCast<domKinematics_model_technique>(kmodel->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00576 addJoints(technique);
00577
00578
00579
00580 int link_num = 0;
00581 addKinematicLink(robot_.getRoot(), technique, link_num);
00582
00583
00584
00585 for (map<string, shared_ptr<urdf::Joint> >::const_iterator i = robot_.joints_.begin(); i != robot_.joints_.end(); i++) {
00586 shared_ptr<urdf::Joint> urdf_joint = i->second;
00587 if( !!urdf_joint->mimic ) {
00588 string joint_sid = string("k1/")+joint_sids_[urdf_joint->name];
00589 string joint_mimic_sid = string("k1/")+joint_sids_[urdf_joint->mimic->joint_name];
00590
00591 addMimicJoint(daeSafeCast<domFormula>(technique->add(COLLADA_ELEMENT_FORMULA)), joint_sid,joint_mimic_sid,urdf_joint->mimic->multiplier,urdf_joint->mimic->offset);
00592
00593 }
00594 }
00595 }
00596 kmodel_ = kmodel;
00597
00598
00599 string model_id = kmodel->getID();
00600 string inst_model_sid = string("inst_") + model_id;
00601
00602
00603 domInstance_kinematics_modelRef ikm = daeSafeCast<domInstance_kinematics_model>(scene.kscene->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_MODEL));
00604 ikm->setUrl((string("#") + model_id).c_str());
00605 ikm->setSid(inst_model_sid.c_str());
00606 {
00607
00608 domKinematics_newparamRef newparam_model = daeSafeCast<domKinematics_newparam>(ikm->add(COLLADA_ELEMENT_NEWPARAM));
00609 string newparam_model_sid = string("kscene.inst_") + model_id;
00610 newparam_model->setSid(newparam_model_sid.c_str());
00611 {
00612
00613 string model_sidref = string("kscene/inst_") + model_id;
00614 daeSafeCast<domKinematics_newparam::domSIDREF>(newparam_model->add(COLLADA_ELEMENT_SIDREF))->setValue(model_sidref.c_str());
00615 }
00616
00617
00618 for (map<string, shared_ptr<urdf::Joint> >::const_iterator i = robot_.joints_.begin(); i != robot_.joints_.end(); i++) {
00619 shared_ptr<urdf::Joint> urdf_joint = i->second;
00620
00621 int idof = 0;
00622
00623 string joint_sid = joint_sids_[urdf_joint->name];
00624
00625 string axis_name = string("axis") + boost::lexical_cast<string>(idof);
00626
00627
00628 domKinematics_newparamRef newparam = daeSafeCast<domKinematics_newparam>(ikm->add(COLLADA_ELEMENT_NEWPARAM));
00629 string newparam_sid = string("kscene.inst_") + model_id + string(".") + joint_sid + string(".") + axis_name;
00630 newparam->setSid(newparam_sid.c_str());
00631 {
00632
00633 string sidref = string("kscene/inst_") + model_id + string("/") + joint_sid + string("/") + axis_name;
00634 daeSafeCast<domKinematics_newparam::domSIDREF>(newparam->add(COLLADA_ELEMENT_SIDREF))->setValue(sidref.c_str());
00635 }
00636
00637
00638
00639 domKinematics_newparamRef newparam_value = daeSafeCast<domKinematics_newparam>(ikm->add(COLLADA_ELEMENT_NEWPARAM));
00640 string newparam_value_sid = string("kscene.inst_") + model_id + string(".") + joint_sid + string(".") + axis_name + string("_value");
00641 newparam_value->setSid(newparam_value_sid.c_str());
00642 {
00643
00644 daeSafeCast<domKinematics_newparam::domFloat>(newparam_value->add(COLLADA_ELEMENT_FLOAT))->setValue(0.0f);
00645 }
00646
00647 }
00648 }
00649
00650 }
00651
00652 void ColladaWriter::addKinematicLink(shared_ptr<const urdf::Link> urdf_link, daeElementRef parent, int& link_num) {
00653
00654 domLinkRef link = daeSafeCast<domLink>(parent->add(COLLADA_ELEMENT_LINK));
00655 string link_sid = string("link") + boost::lexical_cast<string>(link_num);
00656 link->setName(urdf_link->name.c_str());
00657 link->setSid(link_sid.c_str());
00658 link_num++;
00659 foreach(shared_ptr<urdf::Joint> urdf_joint, urdf_link->child_joints) {
00660
00661 domLink::domAttachment_fullRef attachment_full = daeSafeCast<domLink::domAttachment_full>(link->add(COLLADA_ELEMENT_ATTACHMENT_FULL));
00662 string attachment_joint = string("k1/") + joint_sids_[urdf_joint->name];
00663 attachment_full->setJoint(attachment_joint.c_str());
00664 {
00665
00666 addTranslate(attachment_full, urdf_joint->parent_to_joint_origin_transform.position, NULL, true);
00667
00668 addRotate(attachment_full, urdf_joint->parent_to_joint_origin_transform.rotation, NULL, true);
00669
00670 addKinematicLink(robot_.getLink(urdf_joint->child_link_name), attachment_full, link_num);
00671 }
00672
00673 }
00674
00675 }
00676
00677 void ColladaWriter::addVisuals(SCENE const& scene) {
00678
00679 domNodeRef root_node = daeSafeCast<domNode>(scene.vscene->add(COLLADA_ELEMENT_NODE));
00680 root_node->setId("v1");
00681 root_node->setName(robot_.getName().c_str());
00682 {
00683 int link_num = 0;
00684 addVisualLink(robot_.getRoot(), root_node, link_num);
00685 }
00686 }
00687
00688 void ColladaWriter::addMaterials() {
00689 urdf::Color ambient, diffuse;
00690 ambient.init("1 1 1 0");
00691 diffuse.init("1 1 1 0");
00692
00693 for (map<string, shared_ptr<urdf::Link> >::const_iterator i = robot_.links_.begin(); i != robot_.links_.end(); i++) {
00694 shared_ptr<urdf::Link> urdf_link = i->second;
00695
00696 map<string, string>::const_iterator j = geometry_ids_.find(urdf_link->name);
00697 if (j == geometry_ids_.end())
00698 continue;
00699
00700 if (!urdf_link->visual->material->texture_filename.empty()) {
00701 ambient.r = ambient.g = ambient.b = 1; ambient.a = 0;
00702 diffuse.r = diffuse.g = diffuse.b = 1; diffuse.a = 0;
00703 }
00704 else {
00705 ambient.r = diffuse.r = urdf_link->visual->material->color.r;
00706 ambient.g = diffuse.g = urdf_link->visual->material->color.g;
00707 ambient.b = diffuse.b = urdf_link->visual->material->color.b;
00708 ambient.a = diffuse.a = urdf_link->visual->material->color.a;
00709 }
00710
00711 string geometry_id = j->second;
00712
00713 domEffectRef effect = addEffect(geometry_id, ambient, diffuse);
00714
00715
00716 domMaterialRef material = daeSafeCast<domMaterial>(materialsLib_->add(COLLADA_ELEMENT_MATERIAL));
00717 string material_id = geometry_id + string(".mat");
00718 material->setId(material_id.c_str());
00719 {
00720
00721 domInstance_effectRef instance_effect = daeSafeCast<domInstance_effect>(material->add(COLLADA_ELEMENT_INSTANCE_EFFECT));
00722 string effect_id(effect->getId());
00723 instance_effect->setUrl((string("#") + effect_id).c_str());
00724 }
00725
00726 }
00727 }
00728
00729 domEffectRef ColladaWriter::addEffect(string const& geometry_id, urdf::Color const& color_ambient, urdf::Color const& color_diffuse)
00730 {
00731
00732 domEffectRef effect = daeSafeCast<domEffect>(effectsLib_->add(COLLADA_ELEMENT_EFFECT));
00733 string effect_id = geometry_id + string(".eff");
00734 effect->setId(effect_id.c_str());
00735 {
00736
00737 domProfile_commonRef profile = daeSafeCast<domProfile_common>(effect->add(COLLADA_ELEMENT_PROFILE_COMMON));
00738 {
00739
00740 domProfile_common::domTechniqueRef technique = daeSafeCast<domProfile_common::domTechnique>(profile->add(COLLADA_ELEMENT_TECHNIQUE));
00741 {
00742
00743 domProfile_common::domTechnique::domPhongRef phong = daeSafeCast<domProfile_common::domTechnique::domPhong>(technique->add(COLLADA_ELEMENT_PHONG));
00744 {
00745
00746 domFx_common_color_or_textureRef ambient = daeSafeCast<domFx_common_color_or_texture>(phong->add(COLLADA_ELEMENT_AMBIENT));
00747 {
00748
00749 domFx_common_color_or_texture::domColorRef ambient_color = daeSafeCast<domFx_common_color_or_texture::domColor>(ambient->add(COLLADA_ELEMENT_COLOR));
00750 ambient_color->getValue().setCount(4);
00751 ambient_color->getValue()[0] = color_ambient.r;
00752 ambient_color->getValue()[1] = color_ambient.g;
00753 ambient_color->getValue()[2] = color_ambient.b;
00754 ambient_color->getValue()[3] = color_ambient.a;
00755
00756 }
00757
00758
00759
00760 domFx_common_color_or_textureRef diffuse = daeSafeCast<domFx_common_color_or_texture>(phong->add(COLLADA_ELEMENT_DIFFUSE));
00761 {
00762
00763 domFx_common_color_or_texture::domColorRef diffuse_color = daeSafeCast<domFx_common_color_or_texture::domColor>(diffuse->add(COLLADA_ELEMENT_COLOR));
00764 diffuse_color->getValue().setCount(4);
00765 diffuse_color->getValue()[0] = color_diffuse.r;
00766 diffuse_color->getValue()[1] = color_diffuse.g;
00767 diffuse_color->getValue()[2] = color_diffuse.b;
00768 diffuse_color->getValue()[3] = color_diffuse.a;
00769
00770 }
00771
00772 }
00773
00774 }
00775
00776 }
00777
00778 }
00779
00780
00781 return effect;
00782 }
00783
00784 void ColladaWriter::addVisualLink(shared_ptr<urdf::Link const> urdf_link, daeElementRef parent, int& link_num) {
00785
00786 domNodeRef node = daeSafeCast<domNode>(parent->add(COLLADA_ELEMENT_NODE));
00787 string node_sid = string("node") + boost::lexical_cast<string>(link_num);
00788 string node_id = string("v1.") + node_sid;
00789 node->setName(urdf_link->name.c_str());
00790 node->setSid(node_sid.c_str());
00791 node->setId(node_id.c_str());
00792 link_num++;
00793
00794 domNodeRef parent_node = node;
00795
00796 {
00797 if (!!urdf_link->parent_joint) {
00798
00799 addTranslate(node, urdf_link->parent_joint->parent_to_joint_origin_transform.position, NULL, true);
00800
00801 addRotate(node, urdf_link->parent_joint->parent_to_joint_origin_transform.rotation, NULL, true);
00802
00803 domRotateRef joint_rotate;
00804
00805
00806
00807 joint_rotate = daeSafeCast<domRotate>(parent_node->add(COLLADA_ELEMENT_ROTATE));
00808 joint_rotate->getValue().setCount(4);
00809 joint_rotate->getValue()[0] = urdf_link->parent_joint->axis.x;
00810 joint_rotate->getValue()[1] = urdf_link->parent_joint->axis.y;
00811 joint_rotate->getValue()[2] = urdf_link->parent_joint->axis.z;
00812 joint_rotate->getValue()[3] = 0;
00813
00814 string joint_sid = joint_sids_[urdf_link->parent_joint->name];
00815 string joint_rotate_sid = string("node_") + joint_sid + string("_axis0");
00816 joint_rotate->setSid(joint_rotate_sid.c_str());
00817
00818 node_ids_[urdf_link->parent_joint->name] = node_id;
00819 }
00820
00821 if (!!urdf_link->visual) {
00822
00823 domNodeRef visual_node = daeSafeCast<domNode>(node->add(COLLADA_ELEMENT_NODE));
00824 string visual_sid("visual");
00825 string visual_id = node_id + "." + visual_sid;
00826 visual_node->setName("visual");
00827 visual_node->setSid(visual_sid.c_str());
00828 visual_node->setId(visual_id.c_str());
00829 parent_node = visual_node;
00830
00831
00832 addTranslate(parent_node, urdf_link->visual->origin.position, NULL, true);
00833
00834 addRotate(parent_node, urdf_link->visual->origin.rotation, NULL, true);
00835 }
00836
00837
00838 map<string, string>::const_iterator i = geometry_ids_.find(urdf_link->name);
00839 if (i != geometry_ids_.end()) {
00840 domInstance_geometryRef instance_geometry = daeSafeCast<domInstance_geometry>(parent_node->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
00841 string geometry_id = i->second;
00842 string instance_geometry_url = string("#") + geometry_id;
00843 instance_geometry->setUrl(instance_geometry_url.c_str());
00844 {
00845
00846 domBind_materialRef bind_material = daeSafeCast<domBind_material>(instance_geometry->add(COLLADA_ELEMENT_BIND_MATERIAL));
00847 {
00848
00849 domBind_material::domTechnique_commonRef technique_common = daeSafeCast<domBind_material::domTechnique_common>(bind_material->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00850 {
00851
00852 domInstance_materialRef instance_material = daeSafeCast<domInstance_material>(technique_common->add(COLLADA_ELEMENT_INSTANCE_MATERIAL));
00853 instance_material->setTarget((instance_geometry_url + string(".mat")).c_str());
00854 instance_material->setSymbol("mat0");
00855
00856 }
00857
00858 }
00859
00860 }
00861 }
00862
00863
00864
00865 foreach(shared_ptr<urdf::Link> link2, urdf_link->child_links)
00866 addVisualLink(link2, node, link_num);
00867
00868 }
00869
00870 }
00871
00872 domTranslateRef ColladaWriter::addTranslate(daeElementRef parent, urdf::Vector3 const& position, daeElementRef before, bool ignore_zero_translations) {
00873 if (ignore_zero_translations && position.x == 0.0 && position.y == 0.0 && position.z == 0.0)
00874 return NULL;
00875
00876
00877 domTranslateRef trans;
00878 if (before) {
00879 trans = daeSafeCast<domTranslate>(parent->createElement(COLLADA_ELEMENT_TRANSLATE));
00880 parent->addBefore(trans, before);
00881 }
00882 else
00883 trans = daeSafeCast<domTranslate>(parent->add(COLLADA_ELEMENT_TRANSLATE));
00884 trans->getValue().setCount(3);
00885 trans->getValue()[0] = position.x;
00886 trans->getValue()[1] = position.y;
00887 trans->getValue()[2] = position.z;
00888 return trans;
00889 }
00890
00891 domRotateRef ColladaWriter::addRotate(daeElementRef parent, urdf::Rotation const& r, daeElementRef before, bool ignore_zero_rotations) {
00892 double ax, ay, az, aa;
00893
00894
00895 double sqr_len = r.x * r.x + r.y * r.y + r.z * r.z;
00896 if (sqr_len > 0) {
00897 aa = 2 * acos(r.w);
00898
00899 double inv_len = 1.0 / sqrt(sqr_len);
00900 ax = r.x * inv_len;
00901 ay = r.y * inv_len;
00902 az = r.z * inv_len;
00903 }
00904 else {
00905 if (ignore_zero_rotations)
00906 return NULL;
00907
00908
00909 aa = 0.0;
00910 ax = 1.0;
00911 ay = 0.0;
00912 az = 0.0;
00913 }
00914
00915
00916 domRotateRef rot;
00917 if (before) {
00918 rot = daeSafeCast<domRotate>(parent->createElement(COLLADA_ELEMENT_ROTATE));
00919 parent->addBefore(rot, before);
00920 }
00921 else
00922 rot = daeSafeCast<domRotate>(parent->add(COLLADA_ELEMENT_ROTATE));
00923 rot->getValue().setCount(4);
00924 rot->getValue()[0] = ax;
00925 rot->getValue()[1] = ay;
00926 rot->getValue()[2] = az;
00927 rot->getValue()[3] = angles::to_degrees(aa);
00928
00929 return rot;
00930 }
00931
00932 void ColladaWriter::addMimicJoint(domFormulaRef formula, const std::string& joint_sid,const std::string& joint_mimic_sid, double multiplier, double offset)
00933 {
00934 string sid = joint_sid+string(".formula");
00935 formula->setSid(sid.c_str());
00936
00937 domCommon_float_or_paramRef ptarget = daeSafeCast<domCommon_float_or_param>(formula->createAndPlace(COLLADA_ELEMENT_TARGET));
00938 daeSafeCast<domCommon_param>(ptarget->createAndPlace(COLLADA_TYPE_PARAM))->setValue(joint_sid.c_str());
00939
00940 domFormula_techniqueRef pftec = daeSafeCast<domFormula_technique>(formula->createAndPlace(COLLADA_ELEMENT_TECHNIQUE_COMMON));
00941
00942
00943 daeElementRef pmath_math = pftec->createAndPlace("math");
00944 daeElementRef pmath_apply = pmath_math->createAndPlace("apply");
00945 {
00946 daeElementRef pmath_plus = pmath_apply->createAndPlace("plus");
00947 daeElementRef pmath_apply1 = pmath_apply->createAndPlace("apply");
00948 {
00949 daeElementRef pmath_times = pmath_apply1->createAndPlace("times");
00950 daeElementRef pmath_const0 = pmath_apply1->createAndPlace("cn");
00951 pmath_const0->setCharData(boost::lexical_cast<string>(multiplier));
00952 daeElementRef pmath_symb = pmath_apply1->createAndPlace("csymbol");
00953 pmath_symb->setAttribute("encoding","COLLADA");
00954 pmath_symb->setCharData(joint_mimic_sid);
00955 }
00956 daeElementRef pmath_const1 = pmath_apply->createAndPlace("cn");
00957 pmath_const1->setCharData(boost::lexical_cast<string>(offset));
00958 }
00959 }
00960
00961 string ColladaWriter::getTimeStampString() const {
00962
00963 boost::posix_time::time_facet* facet = new boost::posix_time::time_facet("%Y-%m-%dT%H:%M:%s");
00964
00965 std::stringstream ss(std::stringstream::in | std::stringstream::out);
00966 ss.imbue(std::locale(ss.getloc(), facet));
00967 ss << boost::posix_time::second_clock::local_time();
00968
00969 string date;
00970 ss >> date;
00971
00972 return date;
00973 }
00974
00975 }