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 #ifndef URDF2GAZEBO_HH
00035 #define URDF2GAZEBO_HH
00036
00037 #include <cstdio>
00038 #include <cstdlib>
00039 #include <cmath>
00040
00041 #include <vector>
00042 #include <string>
00043
00044 #include <sstream>
00045 #include <map>
00046 #include <vector>
00047
00048 #include <urdf/model.h>
00049
00050 #include "LinearMath/btTransform.h"
00051 #include "LinearMath/btVector3.h"
00052
00053 namespace urdf2gazebo
00054 {
00055 double rad2deg(double v) { return v * 180.0 / M_PI; };
00056
00057 class GazeboExtension
00058 {
00059 public:
00060
00061 std::string material;
00062
00063
00064 bool setStaticFlag;
00065 bool turnGravityOff;
00066 bool is_dampingFactor;
00067 double dampingFactor;
00068 bool selfCollide;
00069
00070
00071 bool is_mu1, is_mu2, is_kp, is_kd, is_genTexCoord;
00072 double mu1, mu2, kp, kd;
00073 bool genTexCoord;
00074 bool is_laserRetro;
00075 double laserRetro;
00076
00077
00078 bool is_stopKp, is_stopKd, is_initial_joint_position, is_fudgeFactor;
00079 double stopKp, stopKd, initial_joint_position, fudgeFactor;
00080 bool provideFeedback;
00081
00082
00083 std::vector<TiXmlElement*> copy_block;
00084
00085 GazeboExtension()
00086 {
00087
00088 material.clear();
00089 setStaticFlag = false;
00090 turnGravityOff = false;
00091 is_dampingFactor = false;
00092 is_mu1 = false;
00093 is_mu2 = false;
00094 is_kp = false;
00095 is_kd = false;
00096 is_genTexCoord = false;
00097 selfCollide = false;
00098 is_laserRetro = false;
00099 is_stopKp = false;
00100 is_stopKd = false;
00101 is_initial_joint_position = false;
00102 is_fudgeFactor = false;
00103 provideFeedback = false;
00104 copy_block.clear();
00105 };
00106 };
00107
00108
00109 class URDF2Gazebo
00110 {
00111 public:
00112 URDF2Gazebo();
00113 ~URDF2Gazebo();
00114
00115 std::string values2str(unsigned int count, const double *values, double (*conv)(double));
00116 std::string vector32str(const urdf::Vector3 vector, double (*conv)(double));
00117
00118 void setupTransform(btTransform &transform, urdf::Pose pose);
00119
00120 void addKeyValue(TiXmlElement *elem, const std::string& key, const std::string &value);
00121
00122 void addTransform(TiXmlElement *elem, const::btTransform& transform);
00123
00124 std::string getGazeboValue(TiXmlElement* elem);
00125 void parseGazeboExtension(TiXmlDocument &urdf_in);
00126 void insertGazeboExtensionGeom(TiXmlElement *elem,std::string link_name);
00127 void insertGazeboExtensionVisual(TiXmlElement *elem,std::string link_name);
00128 void insertGazeboExtensionBody(TiXmlElement *elem,std::string link_name);
00129 void insertGazeboExtensionJoint(TiXmlElement *elem,std::string joint_name);
00130 void insertGazeboExtensionRobot(TiXmlElement *elem);
00131
00132 std::string getGeometrySize(boost::shared_ptr<urdf::Geometry> geometry, int *sizeCount, double *sizeVals);
00133
00134 std::string getGeometryBoundingBox(boost::shared_ptr<urdf::Geometry> geometry, double *sizeVals);
00135
00136 void convertLink(TiXmlElement *root, boost::shared_ptr<const urdf::Link> link, const btTransform &transform, bool enforce_limits);
00137
00138 void convert( TiXmlDocument &urdf_in, TiXmlDocument &gazebo_xml_out, bool enforce_limits, urdf::Vector3 initial_xyz, urdf::Vector3 initial_rpy,std::string model_name=std::string(),std::string robot_namespace=std::string(), bool xml_declaration = false);
00139
00140 void walkChildAddNamespace(TiXmlNode* robot_xml,std::string robot_namespace);
00141
00142 std::map<std::string, GazeboExtension* > gazebo_extensions_;
00143
00144 };
00145 }
00146
00147 #endif