All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
parser_urdf.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef URDF2GAZEBO_HH
18 #define URDF2GAZEBO_HH
19 
20 #include <urdf_model/model.h>
21 #include <urdf_model/link.h>
22 #include <tinyxml.h>
23 
24 #include <cstdio>
25 #include <cstdlib>
26 #include <cmath>
27 #include <vector>
28 #include <string>
29 #include <sstream>
30 #include <map>
31 
32 #include "ode/mass.h"
33 #include "ode/rotation.h"
34 
35 #include "gazebo/math/Pose.hh"
36 #include "gazebo/common/Console.hh"
37 
40 namespace urdf2gazebo
41 {
44 
45  typedef boost::shared_ptr<urdf::Collision> UrdfCollisionPtr;
46  typedef boost::shared_ptr<urdf::Visual> UrdfVisualPtr;
47  typedef boost::shared_ptr<urdf::Link> UrdfLinkPtr;
48  typedef boost::shared_ptr<const urdf::Link> ConstUrdfLinkPtr;
49 
52  {
53  private: GazeboExtension()
54  {
55  material.clear();
56  setStaticFlag = false;
57  gravity = true;
58  isDampingFactor = false;
59  isMaxVel = false;
60  isMinDepth = false;
61  fdir1.clear();
62  isMu1 = false;
63  isMu2 = false;
64  isKp = false;
65  isKd = false;
66  selfCollide = false;
67  isLaserRetro = false;
68  isStopCfm = false;
69  isStopErp = false;
70  isInitialJointPosition = false;
71  isFudgeFactor = false;
72  provideFeedback = false;
73  cfmDamping = false;
74  blobs.clear();
75 
76  dampingFactor = 0;
77  maxVel = 0;
78  minDepth = 0;
79  mu1 = 0;
80  mu2 = 0;
81  kp = 100000000;
82  kd = 1;
83  laserRetro = 101;
84  stopCfm = 0;
85  stopErp = 0.1;
86  initialJointPosition = 0;
87  fudgeFactor = 1;
88  };
89 
90  private: GazeboExtension(const GazeboExtension &ge)
91  {
92  material = ge.material;
93  setStaticFlag = ge.setStaticFlag;
94  gravity = ge.gravity;
95  isDampingFactor = ge.isDampingFactor;
96  isMaxVel = ge.isMaxVel;
97  isMinDepth = ge.isMinDepth;
98  fdir1 = ge.fdir1;
99  isMu1 = ge.isMu1;
100  isMu2 = ge.isMu2;
101  isKp = ge.isKp;
102  isKd = ge.isKd;
103  selfCollide = ge.selfCollide;
104  isLaserRetro = ge.isLaserRetro;
105  isStopCfm = ge.isStopCfm;
106  isStopErp = ge.isStopErp;
107  isInitialJointPosition = ge.isInitialJointPosition;
108  isFudgeFactor = ge.isFudgeFactor;
109  provideFeedback = ge.provideFeedback;
110  cfmDamping = ge.cfmDamping;
111  oldLinkName = ge.oldLinkName;
112  reductionTransform = ge.reductionTransform;
113  blobs = ge.blobs;
114 
115  dampingFactor = ge.dampingFactor;
116  maxVel = ge.maxVel;
117  minDepth = ge.minDepth;
118  mu1 = ge.mu1;
119  mu2 = ge.mu2;
120  kp = ge.kp;
121  kd = ge.kd;
122  laserRetro = ge.laserRetro;
123  stopCfm = ge.stopCfm;
124  stopErp = ge.stopErp;
125  initialJointPosition = ge.initialJointPosition;
126  fudgeFactor = ge.fudgeFactor;
127  };
128 
129  // for reducing fixed joints and removing links
130  private: std::string oldLinkName;
131  private: gazebo::math::Pose reductionTransform;
132 
133  // visual
134  private: std::string material;
135 
136  // body, default off
137  private: bool setStaticFlag;
138  private: bool gravity;
139  private: bool isDampingFactor;
140  private: double dampingFactor;
141  private: bool isMaxVel;
142  private: double maxVel;
143  private: bool isMinDepth;
144  private: double minDepth;
145  private: bool selfCollide;
146 
147  // geom, contact dynamics
148  private: bool isMu1, isMu2, isKp, isKd;
149  private: double mu1, mu2, kp, kd;
150  private: std::string fdir1;
151  private: bool isLaserRetro;
152  private: double laserRetro;
153 
154  // joint, joint limit dynamics
155  private: bool isStopCfm, isStopErp, isInitialJointPosition, isFudgeFactor;
156  private: double stopCfm, stopErp, initialJointPosition, fudgeFactor;
157  private: bool provideFeedback;
158  private: bool cfmDamping;
159 
160  // blobs into body or robot
161  private: std::vector<TiXmlElement*> blobs;
162 
163  friend class URDF2Gazebo;
164  };
165 
167  {
169  public: URDF2Gazebo();
170 
172  public: ~URDF2Gazebo();
173 
177  public: TiXmlDocument InitModelDoc(TiXmlDocument* _xmlDoc);
178 
182  public: TiXmlDocument InitModelFile(const std::string &_filename);
183 
189  public: TiXmlDocument InitModelString(const std::string &_urdfStr,
190  bool _enforceLimits = true);
191 
196  private: urdf::Vector3 ParseVector3(TiXmlNode* _key, double _scale = 1.0);
197 
202  private: std::string Values2str(unsigned int _count, const double *_values);
203 
207  private: std::string Vector32Str(const urdf::Vector3 _vector);
208 
213  private: void AddKeyValue(TiXmlElement *_elem, const std::string &_key,
214  const std::string &_value);
215 
217  private: void AddTransform(TiXmlElement *_elem,
218  const::gazebo::math::Pose& _transform);
219 
221  private: void PrintMass(UrdfLinkPtr _link);
222 
224  private: void PrintMass(const std::string &_linkName, dMass _mass);
225 
227  private: std::string GetKeyValueAsString(TiXmlElement* _elem);
228 
231  private: void ParseGazeboExtension(TiXmlDocument &_urdfXml);
232 
234  private: void InsertGazeboExtensionCollision(TiXmlElement *_elem,
235  const std::string &_linkName);
236 
238  private: void InsertGazeboExtensionVisual(TiXmlElement *_elem,
239  const std::string &_linkName);
240 
242  private: void InsertGazeboExtensionLink(TiXmlElement *_elem,
243  const std::string &_linkName);
244 
246  private: void InsertGazeboExtensionJoint(TiXmlElement *_elem,
247  const std::string &_jointName);
248 
250  private: void InsertGazeboExtensionRobot(TiXmlElement *_elem);
251 
253  private: void ListGazeboExtensions();
254 
256  private: void ListGazeboExtensions(const std::string &_reference);
257 
259  // collision elements of the child link into the parent link
260  private: void ReduceFixedJoints(TiXmlElement *_root, UrdfLinkPtr _link);
261 
263  private: void ReduceInertialToParent(UrdfLinkPtr _link);
264 
266  private: void ReduceVisualsToParent(UrdfLinkPtr _link);
267 
269  private: void ReduceCollisionsToParent(UrdfLinkPtr _link);
270 
272  private: void ReduceJointsToParent(UrdfLinkPtr _link);
273 
275  private: void ReduceVisualToParent(UrdfLinkPtr _link,
276  const std::string &_groupName,
277  UrdfVisualPtr _visual);
278 
280  private: void ReduceCollisionToParent(UrdfLinkPtr _link,
281  const std::string &_groupName,
282  UrdfCollisionPtr _collision);
283 
294  private: void ReduceGazeboExtensionToParent(UrdfLinkPtr _link);
295 
298  private: void ReduceGazeboExtensionFrameReplace(GazeboExtension* _ge,
299  UrdfLinkPtr _link);
300 
303  private: void ReduceGazeboExtensionPluginFrameReplace(
304  std::vector<TiXmlElement*>::iterator _blobIt,
305  UrdfLinkPtr _link, const std::string &_pluginName,
306  const std::string &_elementName, gazebo::math::Pose _reductionTransform);
307 
310  private: void ReduceGazeboExtensionProjectorFrameReplace(
311  std::vector<TiXmlElement*>::iterator _blobIt,
312  UrdfLinkPtr _link);
313 
316  private: void ReduceGazeboExtensionGripperFrameReplace(
317  std::vector<TiXmlElement*>::iterator _blobIt,
318  UrdfLinkPtr _link);
319 
322  private: void ReduceGazeboExtensionJointFrameReplace(
323  std::vector<TiXmlElement*>::iterator _blobIt,
324  UrdfLinkPtr _link);
325 
328  private: void ReduceGazeboExtensionContactSensorFrameReplace(
329  std::vector<TiXmlElement*>::iterator _blobIt,
330  UrdfLinkPtr _link);
331 
334  private: void ReduceGazeboExtensionsTransform(GazeboExtension* _ge);
335 
338  private: void ReduceGazeboExtensionSensorTransformReduction(
339  std::vector<TiXmlElement*>::iterator _blobIt,
340  gazebo::math::Pose _reductionTransform);
341 
344  private: void ReduceGazeboExtensionProjectorTransformReduction(
345  std::vector<TiXmlElement*>::iterator _blobIt,
346  gazebo::math::Pose _reductionTransform);
347 
349  private: urdf::Pose TransformToParentFrame(
350  urdf::Pose _transformInLinkFrame,
351  urdf::Pose _parentToLinkTransform);
353  private: gazebo::math::Pose TransformToParentFrame(
354  gazebo::math::Pose _transformInLinkFrame,
355  urdf::Pose _parentToLinkTransform);
357  private: gazebo::math::Pose TransformToParentFrame(
358  gazebo::math::Pose _transformInLinkFrame,
359  gazebo::math::Pose _parentToLinkTransform);
361  private: gazebo::math::Pose inverseTransformToParentFrame(
362  gazebo::math::Pose _transformInLinkFrame,
363  urdf::Pose _parentToLinkTransform);
366  private: gazebo::math::Pose CopyPose(urdf::Pose _pose);
369  private: urdf::Pose CopyPose(gazebo::math::Pose _pose);
370 
371  private: std::string GetGeometryBoundingBox(
372  boost::shared_ptr<urdf::Geometry> _geometry, double *_sizeVals);
373 
374 
376  private: void PrintCollisionGroups(UrdfLinkPtr _link);
377 
379  private: void CreateSDF(TiXmlElement *_root,
380  ConstUrdfLinkPtr _link,
381  const gazebo::math::Pose &_transform);
382 
384  private: void CreateLink(TiXmlElement *_root,
385  ConstUrdfLinkPtr _link,
386  gazebo::math::Pose &_currentTransform);
387 
389  private: void CreateCollisions(TiXmlElement* _elem,
390  ConstUrdfLinkPtr _link);
391 
393  private: void CreateVisuals(TiXmlElement* _elem,
394  ConstUrdfLinkPtr _link);
395 
397  private: void CreateInertial(TiXmlElement *_elem,
398  ConstUrdfLinkPtr _link);
399 
401  private: void CreateCollision(TiXmlElement* _elem,
402  ConstUrdfLinkPtr _link,
403  UrdfCollisionPtr _collision,
404  const std::string &_oldLinkName = std::string(""));
405 
407  private: void CreateVisual(TiXmlElement *_elem,
408  ConstUrdfLinkPtr _link,
409  UrdfVisualPtr _visual,
410  const std::string &_oldLinkName = std::string(""));
411 
413  private: void CreateJoint(TiXmlElement *_root,
414  ConstUrdfLinkPtr _link,
415  gazebo::math::Pose &_currentTransform);
416 
418  private: void CreateGeometry(TiXmlElement* _elem,
419  boost::shared_ptr<urdf::Geometry> _geometry);
420 
421  private: std::map<std::string, std::vector<GazeboExtension*> > extensions;
422 
423  private: bool enforceLimits;
424  private: bool reduceFixedJoints;
425  };
427 }
428 
429 #endif