collada_to_graphviz.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redstributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 // this program was modified from urdf_to_graphviz.cpp
00036 
00037 #include "collada_parser/collada_parser.h"
00038 #include "urdf/model.h"
00039 #include <iostream>
00040 #include <fstream>
00041 
00042 using namespace urdf;
00043 using namespace std;
00044 
00045 #define PRINT_ORIGIN(os, origin) \
00046 os << "xyz: " << origin.position.x << " " << origin.position.y << " " << origin.position.z << " "; \
00047 { double r,p,y; origin.rotation.getRPY(r, p, y); \
00048   os << "rpy: " << r << " " << p << " " << y; }
00049 
00050 #define PRINT_ORIGIN_XML(os, origin) \
00051   os << "xyz=\"" << origin.position.x << " " << origin.position.y << " " << origin.position.z << "\""; \
00052   { double r,p,y; origin.rotation.getRPY(r, p, y);  os << " rpy=\"" << r << " " << p << " " << y << "\""; }
00053 
00054 #define PRINT_GEOM(os, geometry) \
00055   if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; }
00056 
00057 void addChildLinkNames(boost::shared_ptr<const Link> link, ofstream& os)
00058 {
00059   double r, p, y;
00060   os << "\"" << link->name << "\" [label=\"" << link->name;
00061   if ( link->inertial != NULL ) {
00062     os << "\\n inertial xyz: "
00063        << link->inertial->origin.position.x << " "
00064        << link->inertial->origin.position.y << " "
00065        << link->inertial->origin.position.z << " ";
00066     link->inertial->origin.rotation.getRPY(r, p, y);
00067     os << "rpy: " << r << " " << p << " " << y << "\\n";
00068     os << "mass: " << link->inertial->mass << " ";
00069     os << "matrix: "
00070        << link->inertial->ixx << " "
00071        << link->inertial->ixy << " "
00072        << link->inertial->ixz << " "
00073        << link->inertial->iyy << " "
00074        << link->inertial->iyz << " "
00075        << link->inertial->izz << "\\n";
00076     //os << "\"];" << endl;
00077   } else {
00078     //os << "\"];" << endl;
00079   }
00080 
00081   if ( !!link->visual ) {
00082     os << "\\n";
00083     os << "visual: ";
00084     PRINT_ORIGIN ( os, link->visual->origin );
00085     os << "\\n";
00086     PRINT_GEOM ( os, link->visual->geometry );
00087     //os << "\\n";
00088   }
00089 
00090   if ( !!link->collision ) {
00091     os << "\\n";
00092     os << "collision: ";
00093     PRINT_ORIGIN ( os, link->collision->origin );
00094     os << "\\n";
00095     PRINT_GEOM ( os, link->collision->geometry );
00096     //os << "\\n";
00097   }
00098 
00099   os << "\"];" << endl;
00100   for (std::vector<boost::shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
00101     addChildLinkNames(*child, os);
00102 }
00103 
00104 void addChildJointNames(boost::shared_ptr<const Link> link, ofstream& os)
00105 {
00106   double r, p, y;
00107   for (std::vector<boost::shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){
00108     (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(r,p,y);
00109     os << "\"" << link->name << "\" -> \"" << (*child)->parent_joint->name 
00110        << "\" [label=\"xyz: "
00111        << (*child)->parent_joint->parent_to_joint_origin_transform.position.x << " " 
00112        << (*child)->parent_joint->parent_to_joint_origin_transform.position.y << " " 
00113        << (*child)->parent_joint->parent_to_joint_origin_transform.position.z << " " 
00114        << "\\nrpy: " << r << " " << p << " " << y << "\"]" << endl;
00115     os << "\"" << (*child)->parent_joint->name << "\" -> \"" << (*child)->name << "\"" << endl;
00116 
00117 
00118     addChildJointNames(*child, os);
00119   }
00120 }
00121 
00122 void printTree(boost::shared_ptr<const Link> link, string file)
00123 {
00124   std::ofstream os;
00125   os.open(file.c_str());
00126   os << "digraph G {" << endl;
00127 
00128   os << "node [shape=box];" << endl;
00129   addChildLinkNames(link, os);
00130 
00131   os << "node [shape=ellipse, color=blue, fontcolor=blue];" << endl;
00132   addChildJointNames(link, os);
00133 
00134   os << "}" << endl;
00135   os.close();
00136 }
00137 
00138 int main(int argc, char** argv)
00139 {
00140   if (argc != 2){
00141     std::cerr << "Usage: urdf_to_graphiz input.xml" << std::endl;
00142     return -1;
00143   }
00144 
00145   // get the entire file
00146   std::string xml_string;
00147   std::fstream xml_file(argv[1], std::fstream::in);
00148   while ( xml_file.good() )
00149   {
00150     std::string line;
00151     std::getline( xml_file, line);
00152     xml_string += (line + "\n");
00153   }
00154   xml_file.close();
00155 
00156   boost::shared_ptr<ModelInterface> robot;
00157   if( xml_string.find("<COLLADA") != std::string::npos )
00158   {
00159     ROS_DEBUG("Parsing robot collada xml string");
00160     robot = parseCollada(xml_string);
00161   }
00162   else
00163   {
00164     ROS_DEBUG("Parsing robot urdf xml string");
00165     robot = parseURDF(xml_string);
00166   }
00167 
00168   if (!robot){
00169     std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
00170     return -1;
00171   }
00172   string output = robot->getName();
00173 
00174   // print entire tree to file
00175   printTree(robot->getRoot(), output+".gv");
00176   cout << "Created file " << output << ".gv" << endl;
00177 
00178   string command = "dot -Tpdf "+output+".gv  -o "+output+".pdf";
00179   system(command.c_str());
00180   cout << "Created file " << output << ".pdf" << endl;
00181 
00182   return 0;
00183 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


collada_tools
Author(s): Yohei Kakiuchi (youhei@jsk.t.u-tokyo.ac.jp)
autogenerated on Sat Mar 23 2013 19:48:48