$search
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 * * Redistributions 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 #include <cstdio> 00036 #include <cstdlib> 00037 00038 #include <vector> 00039 #include <string> 00040 #include <sstream> 00041 00042 #include <gazebo/gazebo.h> 00043 #include <gazebo/GazeboError.hh> 00044 #include <gazebo/World.hh> 00045 #include <gazebo/Model.hh> 00046 00047 #include "ros/ros.h" 00048 #include <boost/program_options.hpp> 00049 00050 #include <gazebo/urdf2gazebo.h> 00051 00052 void usage(const char *progname) 00053 { 00054 printf("\nUsage: %s [options]\n", progname); 00055 printf(" Example: %s --help\n",progname); 00056 printf(" Example: %s -f my_urdf_file.urdf -o gazebo_model.xml\n",progname); 00057 } 00058 00059 namespace po = boost::program_options; 00060 00061 int main(int argc, char **argv) 00062 { 00063 // print usage 00064 if (argc < 2) 00065 { 00066 usage(argv[0]); 00067 exit(1); 00068 } 00069 00070 // Initial pose of model 00071 double initial_x = 0; 00072 double initial_y = 0; 00073 double initial_z = 0; 00074 double initial_rx = 0; 00075 double initial_ry = 0; 00076 double initial_rz = 0; 00077 00078 // parse options 00079 po::options_description v_desc("Allowed options"); 00080 v_desc.add_options() 00081 ("help,h" , "produce this help message") 00082 ("input-filename,f" , po::value<std::string>() , "read input model from file, not from the parameter server, exclusive with -p option.") 00083 ("output-filename,o" , po::value<std::string>() , "write converted gazebo model xml to a file instead, model is not spawned in simulation") 00084 ("model-name" , po::value<std::string>() , "Change name of Gazebo model") 00085 ("skip-joint-limits,s" , "do not enforce joint limits during urdf-->gazebo conversion.") 00086 ("init-x,x" , po::value<double>() , "set initial x position of model, defaults to 0.") 00087 ("init-y,y" , po::value<double>() , "set initial y position of model, defaults to 0.") 00088 ("init-z,z" , po::value<double>() , "set initial z position of model, defaults to 0.") 00089 ("init-roll,R" , po::value<double>() , "set initial roll (rx) of model in radians, defaults to 0. Application orders are r-p-y.") 00090 ("init-pitch,P" , po::value<double>() , "set initial pitch (ry) of model in radians, defaults to 0. Application orders are r-p-y.") 00091 ("init-yaw,Y" , po::value<double>() , "set initial yaw (rz) of model in radians, defaults to 0. Application orders are r-p-y."); 00092 00093 00094 po::options_description desc("Allowed options"); 00095 desc.add(v_desc); 00096 00097 po::positional_options_description p_desc; 00098 00099 po::variables_map vm; 00100 po::store(po::command_line_parser(argc, argv).options(desc).positional(p_desc).run(), vm); 00101 po::notify(vm); 00102 00103 if (vm.count("help")) 00104 { 00105 usage(argv[0]); 00106 std::cout << v_desc << std::endl; 00107 exit(1); 00108 } 00109 00110 // set flag to enforce joint limits, this is hardcoded to true because we do want a model with 00111 // joint limits enforced. 00112 bool enforce_limits = true; 00113 if (vm.count("skip-joint-limits")) 00114 enforce_limits = false; 00115 00116 std::string file_in; 00117 if (vm.count("input-filename")) 00118 file_in = vm["input-filename"].as<std::string>(); 00119 else 00120 file_in.clear(); 00121 00122 std::string file_out; 00123 if (vm.count("output-filename")) 00124 { 00125 file_out = vm["output-filename"].as<std::string>(); 00126 } 00127 00128 std::string model_name; 00129 if (vm.count("model-name")) 00130 { 00131 model_name = vm["model-namename"].as<std::string>(); 00132 } 00133 00134 // Initial pose of model 00135 if (vm.count("init-x")) 00136 { 00137 initial_x = vm["init-x"].as<double>(); 00138 ROS_DEBUG("x: %f",initial_x); 00139 } 00140 if (vm.count("init-y")) 00141 { 00142 initial_y = vm["init-y"].as<double>(); 00143 ROS_DEBUG("y: %f",initial_y); 00144 } 00145 if (vm.count("init-z")) 00146 { 00147 initial_z = vm["init-z"].as<double>(); 00148 ROS_DEBUG("z: %f",initial_z); 00149 } 00150 if (vm.count("init-roll")) 00151 { 00152 initial_rx = vm["init-roll"].as<double>(); 00153 ROS_DEBUG("init-roll: %f",initial_rx); 00154 } 00155 if (vm.count("init-pitch")) 00156 { 00157 initial_ry = vm["init-pitch"].as<double>(); 00158 ROS_DEBUG("init-pitch: %f",initial_ry); 00159 } 00160 if (vm.count("init-yaw")) 00161 { 00162 initial_rz = vm["init-yaw"].as<double>(); 00163 ROS_DEBUG("init-yaw: %f",initial_rz); 00164 } 00165 00166 // setup initial pose vectors 00167 urdf::Vector3 initial_xyz(initial_x, initial_y, initial_z); 00168 urdf::Vector3 initial_rpy(initial_rx*180/M_PI, initial_ry*180/M_PI, initial_rz*180/M_PI); 00169 00170 if (file_out.empty()) 00171 { 00172 ROS_ERROR("Must specify output filename for gazebo model"); 00173 exit(2); 00174 } 00175 00176 // get input xml 00177 std::string xml_string; 00178 if (file_in.empty()) 00179 { 00180 ROS_ERROR("Unable to load robot model from filename"); 00181 exit(2); 00182 } 00183 00184 // read urdf / gazebo model xml from file 00185 TiXmlDocument xml_in(file_in); 00186 xml_in.LoadFile(); 00187 // copy tixml to a string 00188 std::ostringstream stream; 00189 stream << xml_in; 00190 xml_string = stream.str(); 00191 00192 // convert xml string to tinyxml object 00193 TiXmlDocument xml_doc; 00194 xml_doc.Parse(xml_string.c_str()); 00195 00196 // resulting gazebo model XML will be stored here 00197 TiXmlDocument gazebo_model_xml; 00198 00199 // check root xml element to determine if conversion is necessary 00200 if (!xml_doc.FirstChild("robot")) 00201 { 00202 ROS_ERROR("Unable to determine input xml type: input urdf xml must begin with <robot>"); 00203 exit(2); 00204 } 00205 00206 // do convertion / manipulate xml 00207 // convert urdf to gazebo model 00208 urdf2gazebo::URDF2Gazebo u2g; 00209 u2g.convert(xml_doc, gazebo_model_xml, enforce_limits, initial_xyz, initial_rpy, model_name); 00210 00211 // output filename is specified, save converted Gazebo Model XML to a file 00212 if (!gazebo_model_xml.SaveFile(file_out)) 00213 { 00214 printf("Unable to save gazebo model in %s\n", file_out.c_str()); 00215 exit(3); 00216 } 00217 00218 return 0; 00219 } 00220