00001
00002 #include <ros/ros.h>
00003 #include "collada_parser/collada_parser.h"
00004 #include "urdf/model.h"
00005 #include "urdf_parser/urdf_parser.h"
00006
00007
00008 #include <IOSystem.hpp>
00009 #include <IOStream.hpp>
00010 #include <Importer.hpp>
00011 #include <Exporter.hpp>
00012 #include <postprocess.h>
00013 #include <scene.h>
00014
00015 #include <iostream>
00016 #include <fstream>
00017
00018 #include <boost/program_options.hpp>
00019 #include <boost/filesystem/path.hpp>
00020 #include <boost/filesystem/operations.hpp>
00021
00022 #include <tf/LinearMath/Transform.h>
00023 #include <tf/LinearMath/Quaternion.h>
00024
00025 #undef GAZEBO_1_0
00026 #undef GAZEBO_1_3
00027
00028 #define GAZEBO_1_3
00029
00030 using namespace urdf;
00031 using namespace std;
00032
00033 bool use_simple_visual = false;
00034 bool use_simple_collision = false;
00035 bool add_gazebo_description = false;
00036 bool use_assimp_export = false;
00037 bool use_same_collision_as_visual = true;
00038 bool rotate_inertia_frame = true;
00039 bool export_collision_mesh = false;
00040
00041 string mesh_dir = "/tmp";
00042 string arobot_name = "";
00043 string output_file = "";
00044 string mesh_prefix = "";
00045
00046 #define PRINT_ORIGIN(os, origin) \
00047 os << "xyz: " << origin.position.x << " " << origin.position.y << " " << origin.position.z << " "; \
00048 { double r,p,y; origin.rotation.getRPY(r, p, y); \
00049 os << "rpy: " << r << " " << p << " " << y; }
00050
00051 #define PRINT_ORIGIN_XML(os, origin) \
00052 os << "xyz=\"" << origin.position.x << " " << origin.position.y << " " << origin.position.z << "\""; \
00053 { double h___r, h___p, h___y; \
00054 origin.rotation.getRPY(h___r, h___p, h___y); \
00055 os << " rpy=\"" << h___r << " " << h___p << " " << h___y << "\""; }
00056
00057 #define PRINT_GEOM(os, geometry) \
00058 if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; }
00059
00060 void assimp_file_export(std::string fname, std::string ofname,
00061 std::string mesh_type = "collada") {
00062 if (fname.find("file://") == 0) {
00063 fname.erase(0, strlen("file://"));
00064 }
00065
00066 Assimp::Importer importer;
00067 {
00068 bool existing;
00069 importer.SetPropertyBool(AI_CONFIG_IMPORT_COLLADA_IGNORE_UP_DIRECTION, true, &existing);
00070 if(existing) {
00071 fprintf(stderr, ";; OverWrite : Ignore UP_DIRECTION");
00072 }
00073
00074 importer.SetPropertyInteger(AI_CONFIG_PP_SBP_REMOVE,
00075 (int)aiPrimitiveType_POINT |
00076 (int)aiPrimitiveType_LINE, &existing);
00077
00078 }
00079 const aiScene* scene = importer.ReadFile(fname.c_str(),
00080
00081
00082
00083 aiProcess_CalcTangentSpace |
00084
00085 aiProcess_GenNormals |
00086 aiProcess_JoinIdenticalVertices |
00087 aiProcess_ImproveCacheLocality |
00088 aiProcess_LimitBoneWeights |
00089 aiProcess_RemoveRedundantMaterials |
00090 aiProcess_SplitLargeMeshes |
00091 aiProcess_Triangulate |
00092 aiProcess_GenUVCoords |
00093 aiProcess_SortByPType |
00094 aiProcess_FindDegenerates |
00095 aiProcess_FindInvalidData |
00096 aiProcess_FindInstances |
00097 aiProcess_ValidateDataStructure |
00098 aiProcess_OptimizeMeshes |
00099 aiProcess_Debone
00100 );
00101
00102 if (!scene) {
00103 std::string str( importer.GetErrorString() );
00104 std::cerr << ";; " << str << std::endl;
00105 return;
00106 }
00107
00108 Assimp::Exporter aexpt;
00109 aiReturn ret = aexpt.Export(scene, mesh_type, ofname);
00110 if ( ret != AI_SUCCESS ) {
00111 std::string str( "assimp error" );
00112 std::cerr << ";; " << str << std::endl;
00113 }
00114 }
00115
00116
00117 void assimp_calc_bbox(string fname, float &minx, float &miny, float &minz,
00118 float &maxx, float &maxy, float &maxz) {
00119
00120 if (fname.find("file://") == 0) {
00121 fname.erase(0, strlen("file://"));
00122 }
00123
00124 Assimp::Importer importer;
00125 const aiScene* scene = importer.ReadFile(fname.c_str(),
00126 aiProcess_Triangulate |
00127 aiProcess_JoinIdenticalVertices |
00128 aiProcess_SortByPType);
00129
00130
00131 if (!scene) {
00132 std::string str( importer.GetErrorString() );
00133 std::cerr << ";; " << str << std::endl;
00134 return;
00135 }
00136
00137 aiNode *node = scene->mRootNode;
00138
00139 bool found = false;
00140 if(node->mNumMeshes > 0 && node->mMeshes != NULL) {
00141 std::cerr << "Root node has meshes " << node->mMeshes << std::endl;;
00142 found = true;
00143 } else {
00144 for (unsigned int i=0; i < node->mNumChildren; ++i) {
00145 if(node->mChildren[i]->mNumMeshes > 0 && node->mChildren[i]->mMeshes != NULL) {
00146 std::cerr << "Child " << i << " has meshes" << std::endl;
00147 node = node->mChildren[i];
00148 found = true;
00149 break;
00150 }
00151 }
00152 }
00153 if(found == false) {
00154 std::cerr << "Can't find meshes in file" << std::endl;
00155 return;
00156 }
00157
00158 aiMatrix4x4 transform = node->mTransformation;
00159
00160
00161 maxx = maxy = maxz = -100000000.0;
00162 minx = miny = minz = 100000000.0;
00163
00164 std::cerr << ";; num meshes: " << node->mNumMeshes << std::endl;
00165 for (unsigned int m = 0; m < node->mNumMeshes; m++) {
00166 aiMesh *a = scene->mMeshes[node->mMeshes[m]];
00167 std::cerr << ";; num vertices: " << a->mNumVertices << std::endl;
00168
00169 for (unsigned int i = 0 ; i < a->mNumVertices ; ++i) {
00170 aiVector3D p;
00171 p.x = a->mVertices[i].x;
00172 p.y = a->mVertices[i].y;
00173 p.z = a->mVertices[i].z;
00174 p *= transform;
00175
00176 if ( maxx < p.x ) {
00177 maxx = p.x;
00178 }
00179 if ( maxy < p.y ) {
00180 maxy = p.y;
00181 }
00182 if ( maxz < p.z ) {
00183 maxz = p.z;
00184 }
00185 if ( minx > p.x ) {
00186 minx = p.x;
00187 }
00188 if ( miny > p.y ) {
00189 miny = p.y;
00190 }
00191 if ( minz > p.z ) {
00192 minz = p.z;
00193 }
00194 }
00195 }
00196 }
00197
00198 void addChildLinkNamesXML(boost::shared_ptr<const Link> link, ofstream& os)
00199 {
00200 os << " <link name=\"" << link->name << "\">" << endl;
00201 if ( !!link->visual ) {
00202 os << " <visual>" << endl;
00203
00204 if (!use_simple_visual) {
00205 os << " <origin ";
00206 PRINT_ORIGIN_XML(os, link->visual->origin);
00207 os << "/>" << endl;
00208 os << " <geometry>" << endl;
00209 if ( link->visual->geometry->type == urdf::Geometry::MESH ) {
00210 std::string ifname (((urdf::Mesh *)link->visual->geometry.get())->filename);
00211 if (ifname.find("file://") == 0) {
00212 ifname.erase(0, strlen("file://"));
00213 }
00214 std::string ofname (mesh_dir + "/" + link->name + "_mesh.dae");
00215
00216 if (use_assimp_export) {
00217
00218 assimp_file_export (ifname, ofname);
00219 } else {
00220
00221 std::ofstream tmp_os;
00222 tmp_os.open(ofname.c_str());
00223 std::ifstream is;
00224 is.open(ifname.c_str());
00225 std::string buf;
00226 while(is && getline(is, buf)) tmp_os << buf << std::endl;
00227 is.close();
00228 tmp_os.close();
00229 }
00230 if (mesh_prefix != "") {
00231 os << " <mesh filename=\"" << mesh_prefix + "/" + link->name + "_mesh.dae" << "\" scale=\"1 1 1\" />" << endl;
00232 } else {
00233 os << " <mesh filename=\"" << "file://" << ofname << "\" scale=\"1 1 1\" />" << endl;
00234 }
00235 }
00236 os << " </geometry>" << endl;
00237 } else {
00238
00239 float ax,ay,az,bx,by,bz;
00240 if ( link->visual->geometry->type == urdf::Geometry::MESH ) {
00241 assimp_calc_bbox(((urdf::Mesh *)link->visual->geometry.get())->filename,
00242 ax, ay, az, bx, by, bz);
00243 }
00244 os << " <origin ";
00245 urdf::Pose pp = link->visual->origin;
00246
00247 pp.position.x += ( ax + bx ) / 2 ;
00248 pp.position.y += ( ay + by ) / 2 ;
00249 pp.position.z += ( az + bz ) / 2 ;
00250 PRINT_ORIGIN_XML(os, pp);
00251 os << "/>" << endl;
00252
00253 os << " <geometry>" << endl;
00254 os << " <box size=\"" << bx - ax << " " << by - ay << " " << bz - az << "\"/>" << endl;
00255 os << " </geometry>" << endl;
00256 }
00257 os << " </visual>" << endl;
00258 }
00259 if ( !!link->collision ) {
00260 os << " <collision>" << endl;
00261 if (!use_simple_collision) {
00262 os << " <origin ";
00263 PRINT_ORIGIN_XML(os, link->collision->origin);
00264 os << "/>" << endl;
00265 os << " <geometry>" << endl;
00266
00267 if ( link->visual->geometry->type == urdf::Geometry::MESH ) {
00268 std::string ifname;
00269 if (use_same_collision_as_visual) {
00270 ifname.assign (((urdf::Mesh *)link->visual->geometry.get())->filename);
00271 } else {
00272 ifname.assign (((urdf::Mesh *)link->collision->geometry.get())->filename);
00273 }
00274 if (ifname.find("file://") == 0) {
00275 ifname.erase(0, strlen("file://"));
00276 }
00277 std::string oofname;
00278 if (export_collision_mesh) {
00279 oofname = link->name + "_mesh.stl";
00280 } else {
00281 oofname = link->name + "_mesh.dae";
00282 }
00283 std::string ofname = (mesh_dir + "/" + oofname);
00284
00285 if (use_assimp_export) {
00286
00287 if (export_collision_mesh) {
00288 assimp_file_export (ifname, ofname, "stl");
00289 } else {
00290 assimp_file_export (ifname, ofname);
00291 }
00292 } else {
00293
00294 std::ofstream tmp_os;
00295 tmp_os.open(ofname.c_str());
00296 std::ifstream is;
00297 is.open(ifname.c_str());
00298 std::string buf;
00299 while(is && getline(is, buf)) tmp_os << buf << std::endl;
00300 is.close();
00301 tmp_os.close();
00302 }
00303 if (mesh_prefix != "") {
00304 os << " <mesh filename=\"" << mesh_prefix + "/" + oofname;
00305 } else {
00306 os << " <mesh filename=\"" << "file://" << ofname;
00307 }
00308 os << "\" scale=\"1 1 1\" />" << endl;
00309 }
00310 os << " </geometry>" << endl;
00311 } else {
00312
00313 float ax,ay,az,bx,by,bz;
00314 if ( link->visual->geometry->type == urdf::Geometry::MESH ) {
00315 assimp_calc_bbox(std::string ( ((urdf::Mesh *)link->visual->geometry.get())->filename ),
00316 ax, ay, az, bx, by, bz);
00317 }
00318 os << " <origin ";
00319 urdf::Pose pp = link->visual->origin;
00320 pp.position.x += ( ax + bx ) / 2 ;
00321 pp.position.y += ( ay + by ) / 2 ;
00322 pp.position.z += ( az + bz ) / 2 ;
00323 PRINT_ORIGIN_XML(os, pp);
00324 os << "/>" << endl;
00325
00326 os << " <geometry>" << endl;
00327 os << " <box size=\"" << bx - ax << " " << by - ay << " " << bz - az << "\"/>" << endl;
00328 os << " </geometry>" << endl;
00329 }
00330 os << " </collision>" << endl;
00331 }
00332 if ( !!link->inertial ) {
00333 if (!rotate_inertia_frame) {
00334 os << " <inertial>" << endl;
00335 os << " <mass value=\"" << link->inertial->mass << "\" />" << endl;
00336 os << " <origin ";
00337 PRINT_ORIGIN_XML(os, link->inertial->origin);
00338 os << "/>" << endl;
00339 os << " <inertia ixx=\"" << link->inertial->ixx << "\" ";
00340 os << "ixy=\"" << link->inertial->ixy << "\" ";
00341 os << "ixz=\"" << link->inertial->ixz << "\" ";
00342 os << "iyy=\"" << link->inertial->iyy << "\" ";
00343 os << "iyz=\"" << link->inertial->iyz << "\" ";
00344 os << "izz=\"" << link->inertial->izz << "\"/>" << endl;
00345 os << " </inertial>" << endl;
00346 } else {
00347
00348 os << " <inertial>" << endl;
00349 os << " <mass value=\"" << link->inertial->mass << "\" />" << endl;
00350 os << " <origin ";
00351
00352 tf::Quaternion qt (link->inertial->origin.rotation.x,
00353 link->inertial->origin.rotation.y,
00354 link->inertial->origin.rotation.z,
00355 link->inertial->origin.rotation.w);
00356 tf::Matrix3x3 mat (qt);
00357 tf::Matrix3x3 tmat (mat.transpose());
00358 tf::Matrix3x3 imat (link->inertial->ixx, link->inertial->ixy, link->inertial->ixz,
00359 link->inertial->ixy, link->inertial->iyy, link->inertial->iyz,
00360 link->inertial->ixz, link->inertial->iyz, link->inertial->izz);
00361 #define DEBUG_MAT(mat) \
00362 cout << "#2f((" << mat[0][0] << " " << mat[0][1] << " " << mat[0][2] << ")"; \
00363 cout << "(" << mat[1][0] << " " << mat[1][1] << " " << mat[1][2] << ")"; \
00364 cout << "(" << mat[2][0] << " " << mat[2][1] << " " << mat[2][2] << "))" << endl;
00365
00366 #if 0
00367 cout << "#f(" << link->inertial->origin.rotation.w << " ";
00368 cout << link->inertial->origin.rotation.x << " ";
00369 cout << link->inertial->origin.rotation.y << " ";
00370 cout << link->inertial->origin.rotation.z << ")" <<endl;
00371 #endif
00372
00373
00374
00375
00376 imat = ( mat * imat * tmat );
00377
00378
00379
00380 urdf::Pose t_pose (link->inertial->origin);
00381 t_pose.rotation.clear();
00382
00383 PRINT_ORIGIN_XML(os, t_pose);
00384 os << "/>" << endl;
00385
00386 os << " <inertia ixx=\"" << imat[0][0] << "\" ";
00387 os << "ixy=\"" << imat[0][1] << "\" ";
00388 os << "ixz=\"" << imat[0][2] << "\" ";
00389 os << "iyy=\"" << imat[1][1] << "\" ";
00390 os << "iyz=\"" << imat[1][2] << "\" ";
00391 os << "izz=\"" << imat[2][2] << "\"/>" << endl;
00392 os << " </inertial>" << endl;
00393 }
00394 }
00395 os << " </link>" << endl;
00396
00397 #ifdef GAZEBO_1_0
00398 if ( add_gazebo_description ) {
00399 os << " <gazebo reference=\"" << link->name << "\">" << endl;
00400 os << " <material>Gazebo/Grey</material>" << endl;
00401
00402
00403 os << " <turnGravityOff>false</turnGravityOff>" << endl;
00404 os << " </gazebo>" << endl;
00405 }
00406 #endif
00407
00408 #ifdef GAZEBO_1_3
00409 if ( add_gazebo_description ) {
00410 os << " <gazebo reference=\"" << link->name << "\">" << endl;
00411 os << " <mu1>0.9</mu1>" << endl;
00412 os << " <mu2>0.9</mu2>" << endl;
00413 os << " </gazebo>" << endl;
00414 }
00415 #endif
00416
00417 for (std::vector<boost::shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
00418 addChildLinkNamesXML(*child, os);
00419 }
00420
00421 void addChildJointNamesXML(boost::shared_ptr<const Link> link, ofstream& os)
00422 {
00423 double r, p, y;
00424 for (std::vector<boost::shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){
00425 (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(r,p,y);
00426 std::string jtype;
00427 if ( (*child)->parent_joint->type == urdf::Joint::UNKNOWN ) {
00428 jtype = std::string("unknown");
00429 } else if ( (*child)->parent_joint->type == urdf::Joint::REVOLUTE ) {
00430 jtype = std::string("revolute");
00431 } else if ( (*child)->parent_joint->type == urdf::Joint::CONTINUOUS ) {
00432 jtype = std::string("continuous");
00433 } else if ( (*child)->parent_joint->type == urdf::Joint::PRISMATIC ) {
00434 jtype = std::string("prismatic");
00435 } else if ( (*child)->parent_joint->type == urdf::Joint::FLOATING ) {
00436 jtype = std::string("floating");
00437 } else if ( (*child)->parent_joint->type == urdf::Joint::PLANAR ) {
00438 jtype = std::string("planar");
00439 } else if ( (*child)->parent_joint->type == urdf::Joint::FIXED ) {
00440 jtype = std::string("fixed");
00441 } else {
00443 }
00444
00445 os << " <joint name=\"" << (*child)->parent_joint->name << "\" type=\"" << jtype << "\">" << endl;
00446 os << " <parent link=\"" << link->name << "\"/>" << endl;
00447 os << " <child link=\"" << (*child)->name << "\"/>" << endl;
00448 os << " <origin xyz=\"" << (*child)->parent_joint->parent_to_joint_origin_transform.position.x << " ";
00449 os << (*child)->parent_joint->parent_to_joint_origin_transform.position.y << " ";
00450 os << (*child)->parent_joint->parent_to_joint_origin_transform.position.z;
00451 os << "\" rpy=\"" << r << " " << p << " " << y << " " << "\"/>" << endl;
00452 os << " <axis xyz=\"" << (*child)->parent_joint->axis.x << " ";
00453 os << (*child)->parent_joint->axis.y << " " << (*child)->parent_joint->axis.z << "\"/>" << endl;
00454 {
00455 boost::shared_ptr<urdf::Joint> jt((*child)->parent_joint);
00456
00457 if ( !!jt->limits ) {
00458 os << " <limit ";
00459 os << "lower=\"" << jt->limits->lower << "\"";
00460 os << " upper=\"" << jt->limits->upper << "\"";
00461 if (jt->limits->effort == 0.0) {
00462 os << " effort=\"100\"";
00463 } else {
00464 os << " effort=\"" << jt->limits->effort << "\"";
00465 }
00466 os << " velocity=\"" << jt->limits->velocity << "\"";
00467 os << " />" << endl;
00468 }
00469 if ( !!jt->dynamics ) {
00470 os << " <dynamics ";
00471 os << "damping=\"" << jt->dynamics->damping << "\"";
00472 os << " friction=\"" << jt->dynamics->friction << "\"";
00473 os << " />" << endl;
00474 } else {
00475 #if 1
00476 os << " <dynamics ";
00477 os << "damping=\"0.2\"";
00478 os << " friction=\"0\"";
00479 os << " />" << endl;
00480 #endif
00481 }
00482 #ifdef GAZEBO_1_3
00483 #if 0
00484 os << " <safety_controller";
00485 os << " k_position=\"10\"";
00486 os << " k_velocity=\"10\"";
00487 os << " soft_lower_limit=\"-10\"";
00488 os << " soft_upper_limit=\"10\"";
00489 os << "/>" << endl;
00490 #endif
00491 #endif
00492 }
00493
00494 os << " </joint>" << endl;
00495
00496 if ( add_gazebo_description ) {
00497 os << " <transmission type=\"pr2_mechanism_model/SimpleTransmission\" name=\"";
00498 os << (*child)->parent_joint->name << "_trans\" >" << endl;
00499 os << " <actuator name=\"" << (*child)->parent_joint->name << "_motor\" />" << endl;
00500 os << " <joint name=\"" << (*child)->parent_joint->name << "\" />" << endl;
00501 os << " <mechanicalReduction>1</mechanicalReduction>" << endl;
00502
00503
00504 os << " </transmission>" << endl;
00505 #ifdef GAZEBO_1_3
00506 #if 1
00507 os << " <gazebo reference=\"" << (*child)->parent_joint->name << "\">" << endl;
00508 os << " <cfmDamping>0.4</cfmDamping>" << endl;
00509 os << " </gazebo>" << endl;
00510 #endif
00511 #endif
00512 }
00513 addChildJointNamesXML(*child, os);
00514 }
00515 }
00516
00517 void printTreeXML(boost::shared_ptr<const Link> link, string name, string file)
00518 {
00519 std::ofstream os;
00520 os.open(file.c_str());
00521 os << "<?xml version=\"1.0\"?>" << endl;
00522 os << "<robot name=\"" << name << "\"" << endl;
00523 os << " xmlns:xi=\"http://www.w3.org/2001/XInclude\"" << endl;
00524 os << " xmlns:gazebo=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#gz\"" << endl;
00525 os << " xmlns:model=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#model\"" << endl;
00526 os << " xmlns:sensor=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor\"" << endl;
00527 os << " xmlns:body=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#body\"" << endl;
00528 os << " xmlns:geom=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#geom\"" << endl;
00529 os << " xmlns:joint=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#joint\"" << endl;
00530 os << " xmlns:interface=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#interface\"" << endl;
00531 os << " xmlns:rendering=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering\"" << endl;
00532 os << " xmlns:renderable=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable\"" << endl;
00533 os << " xmlns:controller=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller\"" << endl;
00534 os << " xmlns:physics=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#physics\">" << endl;
00535
00536 addChildLinkNamesXML(link, os);
00537
00538 addChildJointNamesXML(link, os);
00539
00540 if ( add_gazebo_description ) {
00541 #ifdef GAZEBO_1_0
00542
00543 os << " <gazebo>" << endl;
00544 os << " <controller:gazebo_ros_controller_manager" << endl;
00545 os << " name=\"gazebo_ros_controller_manager\"" << endl;
00546 os << " plugin=\"libgazebo_ros_controller_manager.so\">" << endl;
00547 os << " <alwaysOn>true</alwaysOn>" << endl;
00548 os << " <updateRate>1000.0</updateRate>" << endl;
00549 os << " </controller:gazebo_ros_controller_manager>" << endl;
00550 os << " </gazebo>" << endl;
00551 #endif
00552 }
00553
00554 os << "</robot>" << endl;
00555 os.close();
00556 }
00557
00558 namespace po = boost::program_options;
00559
00560
00561 int main(int argc, char** argv)
00562 {
00563 string inputfile;
00564
00565 po::options_description desc("Options for collada_to_urdf");
00566 desc.add_options()
00567 ("help", "produce help message")
00568 ("simple_visual,V", "use bounding box for visual")
00569 ("simple_collision,C", "use bounding box for collision")
00570 ("export_collision_mesh", "export collision mesh as STL")
00571 ("add_gazebo_description,G", "add description for using on gazebo")
00572 ("use_assimp_export,A", "use assimp library for exporting mesh")
00573 ("use_collision,U", "use collision geometry (default collision is the same as visual)")
00574 ("original_inertia_rotation,R", "does not rotate inertia frame")
00575 ("robot_name,N", po::value< vector<string> >(), "output robot name")
00576 ("mesh_output_dir", po::value< vector<string> >(), "directory for outputing")
00577 ("mesh_prefix", po::value< vector<string> >(), "prefix of mesh files")
00578 ("output_file,O", po::value< vector<string> >(), "output file")
00579 ("input_file", po::value< vector<string> >(), "input file")
00580 ;
00581
00582 po::positional_options_description p;
00583 p.add("input_file", -1);
00584
00585 po::variables_map vm;
00586 try {
00587 po::store(po::command_line_parser(argc, argv).
00588 options(desc).positional(p).run(), vm);
00589 po::notify(vm);
00590 }
00591 catch (po::error e) {
00592 cerr << ";; option parse error / " << e.what() << endl;
00593 return 1;
00594 }
00595
00596 if (vm.count("help")) {
00597 cout << desc << "\n";
00598 return 1;
00599 }
00600 if (vm.count("simple_visual")) {
00601 use_simple_visual = true;
00602 cerr << ";; Using simple_visual" << endl;
00603 }
00604 if (vm.count("simple_collision")) {
00605 use_simple_collision = true;
00606 cerr << ";; Using simple_collision" << endl;
00607 }
00608 if (vm.count("add_gazebo_description")) {
00609 add_gazebo_description = true;
00610 cerr << ";; Adding gazebo description" << endl;
00611 }
00612 if (vm.count("use_assimp_export")) {
00613 use_assimp_export = true;
00614 cerr << ";; Use assimp export" << endl;
00615 }
00616 if (vm.count("original_inertia_rotation")) {
00617 rotate_inertia_frame = false;
00618 cerr << ";; Does not rotate inertia frame" << endl;
00619 }
00620 if (vm.count("export_collision_mesh")) {
00621 export_collision_mesh = true;
00622 cerr << ";; erxport collision mesh as STL" << endl;
00623 }
00624 if (vm.count("output_file")) {
00625 vector<string> aa = vm["output_file"].as< vector<string> >();
00626 cerr << ";; output file is: "
00627 << aa[0] << endl;
00628 output_file = aa[0];
00629 }
00630 if (vm.count("robot_name")) {
00631 vector<string> aa = vm["robot_name"].as< vector<string> >();
00632 cerr << ";; robot_name is: "
00633 << aa[0] << endl;
00634 arobot_name = aa[0];
00635 }
00636 if (vm.count("mesh_prefix")) {
00637 vector<string> aa = vm["mesh_prefix"].as< vector<string> >();
00638 cerr << ";; mesh_prefix is: "
00639 << aa[0] << endl;
00640 mesh_prefix = aa[0];
00641 }
00642 if (vm.count("mesh_output_dir")) {
00643 vector<string> aa = vm["mesh_output_dir"].as< vector<string> >();
00644 cerr << ";; Mesh output directory is: "
00645 << aa[0] << endl;
00646 mesh_dir = aa[0];
00647
00648 boost::filesystem::path mpath( mesh_dir );
00649 try {
00650 if ( ! boost::filesystem::is_directory(mpath) ) {
00651 boost::filesystem::create_directory ( mpath );
00652 }
00653 }
00654 catch ( boost::filesystem::filesystem_error e ) {
00655 cerr << ";; mesh output directory error / " << e.what() << endl;
00656 return 1;
00657 }
00658 }
00659 if (vm.count("input_file")) {
00660 vector<string> aa = vm["input_file"].as< vector<string> >();
00661 cerr << ";; Input file is: "
00662 << aa[0] << endl;
00663 inputfile = aa[0];
00664 }
00665
00666 std::string xml_string;
00667 std::fstream xml_file(inputfile.c_str(), std::fstream::in);
00668 while ( xml_file.good() )
00669 {
00670 std::string line;
00671 std::getline( xml_file, line);
00672 xml_string += (line + "\n");
00673 }
00674 xml_file.close();
00675
00676 boost::shared_ptr<ModelInterface> robot;
00677 if( xml_string.find("<COLLADA") != std::string::npos )
00678 {
00679 ROS_DEBUG("Parsing robot collada xml string");
00680 robot = parseCollada(xml_string);
00681 }
00682 else
00683 {
00684 ROS_DEBUG("Parsing robot urdf xml string");
00685 robot = parseURDF(xml_string);
00686 }
00687
00688 if (!robot){
00689 std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
00690 return -1;
00691 }
00692
00693 if (arobot_name == "") {
00694 arobot_name = robot->getName();
00695 }
00696 if (output_file == "") {
00697 output_file = arobot_name + ".urdf";
00698 }
00699 printTreeXML (robot->getRoot(), arobot_name, output_file);
00700
00701 return 0;
00702 }