urdf.py
Go to the documentation of this file.
1 # Based on the python URDF implementation by Antonio El Khoury
2 # Available at https://github.com/laas/robot_model_py
3 
4 import string
5 from naoqi_tools.gazeboUrdf import *
6 from xml.dom.minidom import Document
7 from xml.dom import minidom
8 import sys
9 from numpy import array, pi
10 import re
11 import copy
12 
13 HUBO_JOINT_SUFFIX_MASK = r'([HKASEWF][RPY12345])'
14 
15 
16 class Collision(object):
17  """Collision node stores collision geometry for a link."""
18  def __init__(self, geometry=None, origin=None):
19  self.geometry = geometry
20  self.origin = origin
21 
22  @staticmethod
23  def parse(node, verbose=True):
24  c = Collision()
25  for child in children(node):
26  if child.localName == 'geometry':
27  c.geometry = Geometry.parse(child, verbose)
28  elif child.localName == 'origin':
29  c.origin = Pose.parse(child)
30  else:
31  print("Unknown collision element '%s'" % child.localName)
32  return c
33 
34  def to_xml(self, doc):
35  xml = doc.createElement("collision")
36  add(doc, xml, self.geometry)
37  add(doc, xml, self.origin)
38  return xml
39 
40  def to_openrave_xml(self, doc):
41 
42  xml = self.geometry.to_openrave_xml(doc)
43  add_openrave(doc, xml, self.origin)
44  return xml
45 
46  def __str__(self):
47  s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
48  s += "Geometry:\n{0}\n".format(reindent(str(self.geometry), 1))
49  return s
50 
51 
52 class Color(object):
53  """Color node stores color definition for a material or a visual."""
54  def __init__(self, r=0.0, g=0.0, b=0.0, a=0.0):
55  self.rgba = (r, g, b, a)
56 
57  @staticmethod
58  def parse(node):
59  rgba = node.getAttribute("rgba").split()
60  (r, g, b, a) = [float(x) for x in rgba]
61  return Color(r, g, b, a)
62 
63  def to_xml(self, doc):
64  xml = doc.createElement("color")
65  set_attribute(xml, "rgba", self.rgba)
66  return xml
67 
68  def to_openrave_xml(self, doc):
69  return None
70 
71  def __str__(self):
72  return "r: {0}, g: {1}, b: {2}, a: {3}, ".format(
73  self.rgba[0], self.rgba[1], self.rgba[2], self.rgba[3])
74 
75 
76 class Dynamics(object):
77  """Dynamics node stores coefficients that define the dynamics of a joint"""
78  def __init__(self, damping=None, friction=None):
79  self.damping = damping
80  self.friction = friction
81 
82  @staticmethod
83  def parse(node):
84  d = Dynamics()
85  if node.hasAttribute('damping'):
86  d.damping = node.getAttribute('damping')
87  if node.hasAttribute('friction'):
88  d.friction = node.getAttribute('friction')
89  return d
90 
91  def to_xml(self, doc):
92  xml = doc.createElement('dynamics')
93  set_attribute(xml, 'damping', self.damping)
94  set_attribute(xml, 'friction', self.friction)
95  return xml
96 
97  def to_openrave_xml(self, doc):
98  return None
99 
100  def __str__(self):
101  return "Damping: {0}\nFriction: {1}\n".format(self.damping,
102  self.friction)
103 
104 
105 class Geometry(object):
106  """Geometry abstract class define the type of geomerical shape for a visual or collision element"""
107  def __init__(self):
108  None
109 
110  @staticmethod
111  def parse(node, verbose=True):
112  shape = children(node)[0]
113  if shape.localName == 'box':
114  return Box.parse(shape)
115  elif shape.localName == 'cylinder':
116  return Cylinder.parse(shape)
117  elif shape.localName == 'sphere':
118  return Sphere.parse(shape)
119  elif shape.localName == 'mesh':
120  return Mesh.parse(shape)
121  else:
122  if verbose:
123  print("Unknown shape %s" % shape.localName)
124 
125  def __str__(self):
126  return "Geometry abstract class"
127 
128 
129 class Box(Geometry):
130  """Box node stores the dimensions for a rectangular geometry element"""
131  def __init__(self, dims=None):
132  if dims is None:
133  self.dims = None
134  else:
135  self.dims = (dims[0], dims[1], dims[2])
136 
137  @staticmethod
138  def parse(node):
139  dims = node.getAttribute('size').split()
140  return Box([float(a) for a in dims])
141 
142  def to_xml(self, doc):
143  xml = doc.createElement("box")
144  set_attribute(xml, "size", self.dims)
145  geom = doc.createElement('geometry')
146  geom.appendChild(xml)
147  return geom
148 
149  def to_openrave_xml(self, doc):
150  xml = short(doc, "geometry", "type", "box")
151  xml.appendChild(create_element(xml, "extents", self.dims))
152  return xml
153 
154  def __str__(self):
155  return "Dimension: {0}".format(self.dims)
156 
157 
159  """Cylinder node stores the dimensions for a z-rotation invariant geometry element"""
160  def __init__(self, radius=0.0, length=0.0):
161  self.radius = radius
162  self.length = length
163 
164  @staticmethod
165  def parse(node):
166  r = node.getAttribute('radius')
167  l = node.getAttribute('length')
168  return Cylinder(float(r), float(l))
169 
170  def to_xml(self, doc):
171  xml = doc.createElement("cylinder")
172  set_attribute(xml, "radius", self.radius)
173  set_attribute(xml, "length", self.length)
174  geom = doc.createElement('geometry')
175  geom.appendChild(xml)
176  return geom
177 
178  def to_openrave_xml(self, doc):
179  xml = short(doc, "geometry", "type", "cylinder")
180  xml.appendChild(create_element(doc, "height", self.length))
181  xml.appendChild(create_element(doc, "radius", self.radius))
182  return xml
183 
184  def __str__(self):
185  return "Radius: {0}\nLength: {1}".format(self.radius,
186  self.length)
187 
188 
190  """Sphere node stores the dimensions for a rotation invariant geometry element"""
191  def __init__(self, radius=0.0):
192  self.radius = radius
193 
194  @staticmethod
195  def parse(node):
196  r = node.getAttribute('radius')
197  return Sphere(float(r))
198 
199  def to_xml(self, doc):
200  xml = doc.createElement("sphere")
201  set_attribute(xml, "radius", self.radius)
202  geom = doc.createElement('geometry')
203  geom.appendChild(xml)
204  return geom
205 
206  def to_openrave_xml(self, doc):
207  xml = short(doc, "geometry", "type", "sphere")
208  xml.create_child(xml, "radius", self.radius)
209  return xml
210 
211  def __str__(self):
212  return "Radius: {0}".format(self.radius)
213 
214 
215 class Mesh(Geometry):
216  """Mesh node stores the path of the mesh file to be displayed"""
217  def __init__(self, filename=None, scale=1):
218  self.filename = filename
219  self.scale = scale
220 
221  @staticmethod
222  def parse(node):
223  fn = node.getAttribute('filename')
224  s = node.getAttribute('scale')
225  if s == '':
226  s = 1
227  else:
228  xyz = node.getAttribute('scale').split()
229  s = map(float, xyz)
230  return Mesh(fn, s)
231 
232  def to_xml(self, doc):
233  xml = doc.createElement("mesh")
234  set_attribute(xml, "filename", self.filename)
235  if self.scale != 1:
236  set_attribute(xml, "scale", self.scale)
237  geom = doc.createElement('geometry')
238  geom.appendChild(xml)
239  return geom
240 
241  def to_openrave_xml(self, doc):
242  xml = short(doc, "geometry", "type", "trimesh")
243  f = '../meshes/' + self.filename.split('/')[-1]
244  fhull = re.sub(r"Body", "convhull", f)
245  # xml.appendChild(create_element(doc, "render", [f, self.scale]))
246  xml.appendChild(create_element(doc, "data", [fhull, self.scale]))
247  # set_attribute(xml, "render", "true")
248  return xml
249 
250  def __str__(self):
251  return "Filename: {0}\nScale: {1}".format(self.filename, self.scale)
252 
253 
254 class Inertial(object):
255  """Inertial node stores mecanical information of a Link : mass, inertia matrix and origin"""
256  def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0,
257  mass=0.0, origin=None):
258  self.matrix = {}
259  self.matrix['ixx'] = ixx
260  self.matrix['ixy'] = ixy
261  self.matrix['ixz'] = ixz
262  self.matrix['iyy'] = iyy
263  self.matrix['iyz'] = iyz
264  self.matrix['izz'] = izz
265  self.mass = mass
266  self.origin = origin
267 
268  @staticmethod
269  def parse(node):
270  inert = Inertial()
271  for child in children(node):
272  if child.localName == 'inertia':
273  for v in ['ixx', 'ixy', 'ixz', 'iyy', 'iyz', 'izz']:
274  inert.matrix[v] = float(child.getAttribute(v))
275  elif child.localName == 'mass':
276  inert.mass = float(child.getAttribute('value'))
277  elif child.localName == 'origin':
278  inert.origin = Pose.parse(child)
279  return inert
280 
281  def to_xml(self, doc):
282  xml = doc.createElement("inertial")
283 
284  xml.appendChild(short(doc, "mass", "value", self.mass))
285 
286  inertia = doc.createElement("inertia")
287  for (n, v) in self.matrix.items():
288  set_attribute(inertia, n, v)
289  xml.appendChild(inertia)
290 
291  add(doc, xml, self.origin)
292  return xml
293 
294  def to_openrave_xml(self, doc):
295  xml = doc.createElement("mass")
296  set_attribute(xml, "type", "custom")
297  xml.appendChild(create_element(doc, "total", self.mass))
298  text = '{ixx} {ixy} {ixz}\n{ixy} {iyy} {iyz}\n{ixz} {iyz} {izz}'.format(**self.matrix)
299  xml.appendChild(create_element(doc, "inertia", text))
300  add_openrave(doc, xml, self.origin)
301  xml.getElementsByTagName('translation')[0].tagName = "com"
302  return xml
303 
304  def __str__(self):
305  s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
306  s += "Mass: {0}\n".format(self.mass)
307  s += "ixx: {0}\n".format(self.matrix['ixx'])
308  s += "ixy: {0}\n".format(self.matrix['ixy'])
309  s += "ixz: {0}\n".format(self.matrix['ixz'])
310  s += "iyy: {0}\n".format(self.matrix['iyy'])
311  s += "iyz: {0}\n".format(self.matrix['iyz'])
312  s += "izz: {0}\n".format(self.matrix['izz'])
313  return s
314 
315 
316 class Joint(object):
317  """Joint node stores articulation information coupling two links"""
318  UNKNOWN = 'unknown'
319  REVOLUTE = 'revolute'
320  CONTINUOUS = 'continuous'
321  PRISMATIC = 'prismatic'
322  FLOATING = 'floating'
323  PLANAR = 'planar'
324  FIXED = 'fixed'
325 
326  def __init__(self, name, parent, child, joint_type, axis=None, origin=None,
327  limits=None, dynamics=None, safety=None, calibration=None,
328  mimic=None):
329  self.name = name
330  self.parent = parent
331  self.child = child
332  self.joint_type = joint_type
333  self.axis = axis
334  self.origin = origin
335  self.limits = limits
336  self.dynamics = dynamics
337  self.safety = safety
338  self.calibration = calibration
339  self.mimic = mimic
340 
341  @staticmethod
342  def parse(node, verbose=True):
343  joint = Joint(node.getAttribute('name'), None, None,
344  node.getAttribute('type'))
345  for child in children(node):
346  if child.localName == 'parent':
347  joint.parent = child.getAttribute('link')
348  elif child.localName == 'child':
349  joint.child = child.getAttribute('link')
350  elif child.localName == 'axis':
351  joint.axis = array([float(x) for x in child.getAttribute('xyz').split(' ')])
352  elif child.localName == 'origin':
353  joint.origin = Pose.parse(child)
354  elif child.localName == 'limit':
355  joint.limits = JointLimit.parse(child)
356  elif child.localName == 'dynamics':
357  joint.dynamics = Dynamics.parse(child)
358  elif child.localName == 'safety_controller':
359  joint.safety = SafetyController.parse(child)
360  elif child.localName == 'calibration':
361  joint.calibration = JointCalibration.parse(child)
362  elif child.localName == 'mimic':
363  joint.mimic = JointMimic.parse(child)
364  else:
365  if verbose:
366  print("Unknown joint element '%s'" % child.localName)
367  return joint
368 
369  def to_xml(self, doc):
370  xml = doc.createElement("joint")
371  set_attribute(xml, "name", self.name)
372  set_attribute(xml, "type", self.joint_type)
373  xml.appendChild(short(doc, "parent", "link", self.parent))
374  xml.appendChild(short(doc, "child", "link", self.child))
375  add(doc, xml, self.origin)
376  if self.axis is not None:
377  xml.appendChild(short(doc, "axis", "xyz", to_string(self.axis)))
378  add(doc, xml, self.limits)
379  add(doc, xml, self.dynamics)
380  add(doc, xml, self.safety)
381  add(doc, xml, self.calibration)
382  add(doc, xml, self.mimic)
383 
384  return xml
385 
386  def to_openrave_xml(self, doc):
387  xml = doc.createElement("joint")
388  set_attribute(xml, "name", self.name)
389  s = ""
390  if self.joint_type == Joint.UNKNOWN:
391  s = "unknown"
392  elif self.joint_type == Joint.REVOLUTE:
393  s = "hinge"
394  elif self.joint_type == Joint.CONTINUOUS:
395  s = "hinge"
396  set_attribute(xml, "circular", "true")
397  elif self.joint_type == Joint.PRISMATIC:
398  s = "slider"
399  elif self.joint_type == Joint.FIXED:
400  s = "hinge"
401  set_attribute(xml, "enable", "false")
402  xml.appendChild(create_element(doc, "limits", "0 0"))
403 
404  set_attribute(xml, "type", s)
405  if self.mimic is not None:
406  multiplier = self.mimic.multiplier if self.mimic.multiplier is not None else 1.0
407  offset = self.mimic.offset if self.mimic.offset is not None else 0.0
408  # 1) Follow openrave mimic joint format, disable joint:
409  set_attribute(xml, "enable", "false")
410  # 2) Create the position equation
411  set_attribute(xml, "mimic_pos", "{0} * {1} + {2}".format(self.mimic.joint_name, multiplier, offset))
412  set_attribute(xml, "mimic_vel", "|{0} {1}".format(self.mimic.joint_name, multiplier))
413 
414  xml.appendChild(create_element(doc, "body", self.parent))
415  xml.appendChild(create_element(doc, "body", self.child))
416  xml.appendChild(create_element(doc, "offsetfrom", self.parent))
417  add_openrave(doc, xml, self.origin)
418  xml.getElementsByTagName('translation')[0].tagName = "anchor"
419  if self.axis is not None:
420  xml.appendChild(create_element(doc, "axis", self.axis))
421  add_openrave(doc, xml, self.limits)
422  return xml
423 
424  def __str__(self):
425  s = "Name: {0}\n".format(self.name)
426 
427  s += "Child link name: {0}\n".format(self.child)
428  s += "Parent link name: {0}\n".format(self.parent)
429 
430  if self.joint_type == Joint.UNKNOWN:
431  s += "Type: unknown\n"
432  elif self.joint_type == Joint.REVOLUTE:
433  s += "Type: revolute\n"
434  elif self.joint_type == Joint.CONTINUOUS:
435  s += "Type: continuous\n"
436  elif self.joint_type == Joint.PRISMATIC:
437  s += "Type: prismatic\n"
438  elif self.joint_type == Joint.FLOATING:
439  s += "Type: floating\n"
440  elif self.joint_type == Joint.PLANAR:
441  s += "Type: planar\n"
442  elif self.joint_type == Joint.FIXED:
443  s += "Type: fixed\n"
444  else:
445  print("unknown joint type")
446 
447  s += "Axis: {0}\n".format(self.axis)
448  s += "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
449  s += "Limits:\n"
450  s += reindent(str(self.limits), 1) + "\n"
451  s += "Dynamics:\n"
452  s += reindent(str(self.dynamics), 1) + "\n"
453  s += "Safety:\n"
454  s += reindent(str(self.safety), 1) + "\n"
455  s += "Calibration:\n"
456  s += reindent(str(self.calibration), 1) + "\n"
457  s += "Mimic:\n"
458  s += reindent(str(self.mimic), 1) + "\n"
459  return s
460 
461 
462 # FIXME: we are missing the reference position here.
463 class JointCalibration(object):
464  def __init__(self, rising=None, falling=None):
465  self.rising = rising
466  self.falling = falling
467 
468  @staticmethod
469  def parse(node):
470  jc = JointCalibration()
471  if node.hasAttribute('rising'):
472  jc.rising = float(node.getAttribute('rising'))
473  if node.hasAttribute('falling'):
474  jc.falling = float(node.getAttribute('falling'))
475  return jc
476 
477  def to_xml(self, doc):
478  xml = doc.createElement('calibration')
479  set_attribute(xml, 'rising', self.rising)
480  set_attribute(xml, 'falling', self.falling)
481  return xml
482 
483  def to_openrave_xml(self, doc):
484  # No implementation
485  return None
486 
487  def __str__(self):
488  s = "Raising: {0}\n".format(self.rising)
489  s += "Falling: {0}\n".format(self.falling)
490  return s
491 
492 
493 class JointLimit(object):
494  """JointLimit node stores mechanical limits of a given joint"""
495  def __init__(self, effort, velocity, lower=None, upper=None):
496  self.effort = effort
497  self.velocity = velocity
498  self.lower = lower
499  self.upper = upper
500 
501  @staticmethod
502  def parse(node):
503  jl = JointLimit(float(node.getAttribute('effort')),
504  float(node.getAttribute('velocity')))
505  if node.hasAttribute('lower'):
506  jl.lower = float(node.getAttribute('lower'))
507  if node.hasAttribute('upper'):
508  jl.upper = float(node.getAttribute('upper'))
509  return jl
510 
511  def get_from_table(self, node):
512  jl = JointLimit(float(node.getAttribute('effort')),
513  float(node.getAttribute('velocity')))
514  if node.hasAttribute('lower'):
515  jl.lower = float(node.getAttribute('lower'))
516  if node.hasAttribute('upper'):
517  jl.upper = float(node.getAttribute('upper'))
518  return jl
519 
520  def to_xml(self, doc):
521  xml = doc.createElement('limit')
522  set_attribute(xml, 'effort', self.effort)
523  set_attribute(xml, 'velocity', self.velocity)
524  set_attribute(xml, 'lower', self.lower)
525  set_attribute(xml, 'upper', self.upper)
526  return xml
527 
528  def to_openrave_xml(self, doc):
529  limit = create_element(doc, 'limitsdeg', [round(self.lower*180/pi, 1), round(self.upper*180/pi, 1)])
530  maxvel = create_element(doc, 'maxvel', self.velocity)
531  maxtrq = create_element(doc, 'maxtorque', self.effort)
532  return [limit, maxvel, maxtrq]
533 
534  def __str__(self):
535  s = "Effort: {0}\n".format(self.effort)
536  s += "Lower: {0}\n".format(self.lower)
537  s += "Upper: {0}\n".format(self.upper)
538  s += "Velocity: {0}\n".format(self.velocity)
539  return s
540 
541 
542 class JointMimic(object):
543  """JointMimic node stores information coupling an actuated joint to a not controllable joint"""
544  def __init__(self, joint_name, multiplier=None, offset=None):
545  self.joint_name = joint_name
546  self.multiplier = multiplier
547  self.offset = offset
548 
549  @staticmethod
550  def parse(node):
551  mimic = JointMimic(node.getAttribute('joint'))
552  if node.hasAttribute('multiplier'):
553  mimic.multiplier = float(node.getAttribute('multiplier'))
554  if node.hasAttribute('offset'):
555  mimic.offset = float(node.getAttribute('offset'))
556  return mimic
557 
558  def to_xml(self, doc):
559  xml = doc.createElement('mimic')
560  set_attribute(xml, 'joint', self.joint_name)
561  set_attribute(xml, 'multiplier', self.multiplier)
562  set_attribute(xml, 'offset', self.offset)
563  return xml
564 
565  def __str__(self):
566  s = "Joint: {0}\n".format(self.joint_name)
567  s += "Multiplier: {0}\n".format(self.multiplier)
568  s += "Offset: {0}\n".format(self.offset)
569  return s
570 
571 
572 class Link(object):
573  """Link node stores information defining the mechanics and the visualization of a link"""
574  def __init__(self, name, visual=None, inertial=None, collision=None, xacro=None):
575  self.name = name
576  self.visual = visual
577  self.inertial = inertial
578  self.collision = collision
579  self.xacro = xacro
580 
581  @staticmethod
582  def parse(node, verbose=True):
583  link = Link(node.getAttribute('name'))
584  for child in children(node):
585  if child.localName == 'visual':
586  link.visual = Visual.parse(child, verbose)
587  elif child.localName == 'collision':
588  link.collision = Collision.parse(child, verbose)
589  elif child.localName == 'inertial':
590  link.inertial = Inertial.parse(child)
591  elif child.localName.startswith('xacro'):
592  link.xacro = xacro
593  else:
594  if verbose:
595  print("Unknown link element '%s'" % child.localName)
596  return link
597 
598  def to_xml(self, doc):
599  xml = doc.createElement("link")
600  xml.setAttribute("name", self.name)
601  add(doc, xml, self.visual)
602  add(doc, xml, self.collision)
603  add(doc, xml, self.inertial)
604  if self.xacro is not None:
605  text = doc.createElement(self.xacro)
606  xml.appendChild(text)
607  return xml
608 
609  def to_openrave_xml(self, doc):
610  xml = doc.createElement("body")
611  xml.setAttribute("name", self.name)
612  add_openrave(doc, xml, self.collision)
613  add_openrave(doc, xml, self.inertial)
614  return xml
615 
616  def __str__(self):
617  s = "Name: {0}\n".format(self.name)
618  s += "Inertial:\n"
619  s += reindent(str(self.inertial), 1) + "\n"
620  s += "Visual:\n"
621  s += reindent(str(self.visual), 1) + "\n"
622  s += "Collision:\n"
623  s += reindent(str(self.collision), 1) + "\n"
624  s += "Xacro:\n"
625  s += reindent(str(self.xacro), 1) + "\n"
626  return s
627 
628 
629 class Material(object):
630  """Material node stores visual information of a mechanical material : color, texture"""
631  def __init__(self, name=None, color=None, texture=None):
632  self.name = name
633  self.color = color
634  self.texture = texture
635 
636  @staticmethod
637  def parse(node, verbose=True):
638  material = Material()
639  if node.hasAttribute('name'):
640  material.name = node.getAttribute('name')
641  for child in children(node):
642  if child.localName == 'color':
643  material.color = Color.parse(child)
644  elif child.localName == 'texture':
645  material.texture = child.getAttribute('filename')
646  else:
647  if verbose:
648  print("Unknown material element '%s'" % child.localName)
649 
650  return material
651 
652  def to_xml(self, doc):
653  xml = doc.createElement("material")
654  set_attribute(xml, "name", self.name)
655  add(doc, xml, self.color)
656 
657  if self.texture is not None:
658  text = doc.createElement("texture")
659  text.setAttribute('filename', self.texture)
660  xml.appendChild(text)
661  return xml
662 
663  def __str__(self):
664  s = "Name: {0}\n".format(self.name)
665  s += "Color: {0}\n".format(self.color)
666  s += "Texture:\n"
667  s += reindent(str(self.texture), 1)
668  return s
669 
670 
671 class Pose(object):
672  """Pose node stores a cartesian 6-D pose :
673  xyz : array
674  rpy : array
675  """
676  def __init__(self, position=None, rotation=None):
677  self.position = array(position)
678  self.rotation = array(rotation)
679 
680  @staticmethod
681  def parse(node):
682  pose = Pose()
683  if node.hasAttribute("xyz"):
684  xyz = node.getAttribute('xyz').split()
685  pose.position = array(map(float, xyz))
686  if node.hasAttribute("rpy"):
687  rpy = node.getAttribute('rpy').split()
688  pose.rotation = array(map(float, rpy))
689  return pose
690 
691  def to_xml(self, doc):
692  xml = doc.createElement("origin")
693  set_attribute(xml, 'xyz', self.position)
694  set_attribute(xml, 'rpy', self.rotation)
695  return xml
696 
697  def to_openrave_xml(self, doc):
698  xml = doc.createElement("translation")
699  set_content(doc, xml, self.position)
700  elements = [xml]
701  if not self.rotation[0] == 0:
702  rotr = doc.createElement("rotationaxis")
703  set_content(doc, rotr, [1, 0, 0, self.rotation[0] * 180.0/pi])
704  elements.append(rotr)
705  if not self.rotation[1] == 0:
706  rotp = doc.createElement("rotationaxis")
707  set_content(doc, rotp, [0, 1, 0, self.rotation[1] * 180.0/pi])
708  elements.append(rotp)
709  if not self.rotation[2] == 0:
710  roty = doc.createElement("rotationaxis")
711  set_content(doc, roty, [0, 0, 1, self.rotation[2] * 180.0/pi])
712  elements.append(roty)
713 
714  return elements
715 
716  def __str__(self):
717  return "Position: {0}\nRotation: {1}".format(self.position,
718  self.rotation)
719 
720 
721 class SafetyController(object):
722  def __init__(self, velocity, position=None, lower=None, upper=None):
723  self.velocity = velocity
724  self.position = position
725  self.lower = lower
726  self.upper = upper
727 
728  @staticmethod
729  def parse(node):
730  sc = SafetyController(float(node.getAttribute('k_velocity')))
731  if node.hasAttribute('soft_lower_limit'):
732  sc.lower = float(node.getAttribute('soft_lower_limit'))
733  if node.hasAttribute('soft_upper_limit'):
734  sc.upper = float(node.getAttribute('soft_upper_limit'))
735  if node.hasAttribute('k_position'):
736  sc.position = float(node.getAttribute('k_position'))
737  return sc
738 
739  def to_xml(self, doc):
740  xml = doc.createElement('safety_controller')
741  set_attribute(xml, 'k_velocity', self.velocity)
742  set_attribute(xml, 'k_position', self.position)
743  set_attribute(xml, 'soft_upper_limit', self.upper)
744  set_attribute(xml, 'soft_lower_limit', self.lower)
745  return xml
746 
747  def __str__(self):
748  s = "Safe lower limit: {0}\n".format(self.lower)
749  s += "Safe upper limit: {0}\n".format(self.upper)
750  s += "K position: {0}\n".format(self.position)
751  s += "K velocity: {0}\n".format(self.velocity)
752  return s
753 
754 
755 class Visual(object):
756  """Visual node stores information defining shape and material of the link to be displayed"""
757  def __init__(self, geometry=None, material=None, origin=None):
758  self.geometry = geometry
759  self.material = material
760  self.origin = origin
761 
762  @staticmethod
763  def parse(node, verbose=True):
764  v = Visual()
765  for child in children(node):
766  if child.localName == 'geometry':
767  v.geometry = Geometry.parse(child, verbose)
768  elif child.localName == 'origin':
769  v.origin = Pose.parse(child)
770  elif child.localName == 'material':
771  v.material = Material.parse(child, verbose)
772  else:
773  if verbose:
774  print("Unknown visual element '%s'" % child.localName)
775  return v
776 
777  def to_xml(self, doc):
778  xml = doc.createElement("visual")
779  add(doc, xml, self.geometry)
780  add(doc, xml, self.origin)
781  add(doc, xml, self.material)
782  return xml
783 
784  def __str__(self):
785  s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
786  s += "Geometry:\n"
787  s += reindent(str(self.geometry), 1) + "\n"
788  s += "Material:\n"
789  s += reindent(str(self.material), 1) + "\n"
790  return s
791 
792 
793 class Actuator(object):
794  """Actuator node stores information about how a motor controls a joint : used in transmission tags"""
795  def __init__(self, name=None, hardwareInterface=None, mechanicalReduction=1):
796  self.name = name
797  self.hardwareInterface = hardwareInterface
798  self.mechanicalReduction = mechanicalReduction
799 
800  @staticmethod
801  def parse(node, verbose=True):
802  actuator = Actuator()
803  if node.hasAttribute('name'):
804  actuator.name = node.getAttribute('name')
805  for child in children(node):
806  if child.localName == 'hardwareInterface':
807  actuator.hardwareInterface = str(child.childNodes[0].nodeValue)
808  if child.localName == 'mechanicalReduction':
809  actuator.mechanicalReduction = str(child.childNodes[0].nodeValue)
810  else:
811  print'Unknown actuator element ' + str(child.localName)
812  return actuator
813 
814  def to_xml(self, doc):
815  xml = doc.createElement('actuator')
816  set_attribute(xml, 'name', self.name)
817  xml.appendChild(create_element(doc, 'hardwareInterface', self.hardwareInterface))
818  xml.appendChild(create_element(doc, "mechanicalReduction", str(self.mechanicalReduction)))
819  return xml
820 
821  def __str__(self):
822  s = "Name: {0}\n".format(self.name)
823  s += "HardwareInterface : {0}\n".format(self.hardwareInterface)
824  s += "Mechanical Reduction: {0}\n".format(self.mechanicalReduction)
825  return s
826 
827 
828 class Transmission(object):
829  """Transmission node stores information linking a joint to an actuator"""
830  def __init__(self, name=None, type=None, joint=None, actuator=None):
831  self.name = name
832  self.joint = joint
833  self.actuator = actuator
834  self.type = type
835 
836  @staticmethod
837  def parse(node, verbose=True):
838  trans = Transmission()
839  if node.hasAttribute('name'):
840  trans.name = node.getAttribute('name')
841  for child in children(node):
842  if child.localName == 'joint':
843  trans.joint = child.getAttribute('name')
844  if child.localName == 'actuator':
845  trans.actuator = Actuator.parse(child, verbose)
846  if child.localName == 'type':
847  trans.type = str(child.childNodes[0].nodeValue)
848  # str(child.getAttribute('type'))
849  return trans
850 
851  def to_xml(self, doc):
852  xml = doc.createElement('transmission')
853  set_attribute(xml, 'name', self.name)
854  xml.appendChild(short(doc, "joint", "name", self.joint))
855  xml.appendChild(create_element(doc, 'type', self.type))
856  add(doc, xml, self.actuator)
857 
858  return xml
859 
860  def __str__(self):
861  s = "Name: {0}\n".format(self.name)
862  s += "Type: {0}\n".format(self.type)
863  s += "Joint: {0}\n".format(self.joint)
864  s += "Actuator:\n"
865  s += reindent(str(self.actuator), 1) + "\n"
866 
867  return s
868 
869 
870 ########################################
871 ######### URDF Global Class ############
872 ########################################
873 class URDF(object):
874  """URDF node stores every information about a robot's model"""
875  ZERO_THRESHOLD = 0.000000001
876 
877  def __init__(self, name=""):
878  self.name = name
879  self.elements = []
880  self.gazebos = {}
881  self.links = {}
882  self.joints = {}
883  self.materials = {}
884  self.parent_map = {}
885  self.child_map = {}
886 
887  @staticmethod
888  def parse_xml_string(xml_string, verbose=True):
889  """Parse a string to create a URDF robot structure."""
890  urdf = URDF()
891  base = minidom.parseString(xml_string)
892  robot = children(base)[0]
893  urdf.name = robot.getAttribute('name')
894 
895  for node in children(robot):
896  if node.nodeType is node.TEXT_NODE:
897  continue
898  if node.localName == 'joint':
899  urdf.add_joint(Joint.parse(node, verbose))
900  elif node.localName == 'link':
901  urdf.add_link(Link.parse(node, verbose))
902  elif node.localName == 'material':
903  urdf.add_material(Material.parse(node, verbose))
904  elif node.localName == 'gazebo':
905  urdf.add_gazebo(Gazebo.parse(node, verbose))
906  elif node.localName == 'transmission':
907  urdf.elements.append(Transmission.parse(node, verbose))
908  else:
909  if verbose:
910  print("Unknown robot element '%s'" % node.localName)
911  return urdf
912 
913  @staticmethod
914  def load_xml_file(filename, verbose=True):
915  """Parse a file to create a URDF robot structure."""
916  f = open(filename, 'r')
917  return URDF.parse_xml_string(f.read(), verbose)
918 
919  @staticmethod
920  def load_from_parameter_server(key='robot_description', verbose=True):
921  """
922  Retrieve the robot model on the parameter server
923  and parse it to create a URDF robot structure.
924 
925  Warning: this requires roscore to be running.
926  """
927  import rospy
928  return URDF.parse_xml_string(rospy.get_param(key), verbose)
929 
930  def add_link(self, link):
931  self.elements.append(link)
932  self.links[link.name] = link
933 
934  def add_joint(self, joint):
935  self.elements.append(joint)
936  self.joints[joint.name] = joint
937 
938  self.parent_map[joint.child] = (joint.name, joint.parent)
939  if joint.parent in self.child_map:
940  self.child_map[joint.parent].append((joint.name, joint.child))
941  else:
942  self.child_map[joint.parent] = [(joint.name, joint.child)]
943 
944  def add_material(self, material):
945  """
946  Add a material to the URDF.elements list
947  """
948  self.elements.append(material)
949  self.materials[material.name] = material
950 
951  def add_gazebo(self, gazebo):
952  """
953  Add gazebo data to the URDF.elements list
954  """
955 
956  self.elements.append(gazebo)
957  self.gazebos[gazebo.reference] = gazebo
958 
959  def get_chain(self, root, tip, joints=True, links=True, fixed=True):
960  """Based on given link names root and tip, return either a joint or link chain as a list of names."""
961  chain = []
962  if links:
963  chain.append(tip)
964  link = tip
965  while link != root:
966  (joint, parent) = self.parent_map[link]
967  if joints:
968  if fixed or self.joints[joint].joint_type != 'fixed':
969  chain.append(joint)
970  if links:
971  chain.append(parent)
972  link = parent
973  chain.reverse()
974  return chain
975 
976  def get_root(self):
977  root = None
978  for link in self.links:
979  if link not in self.parent_map:
980  assert root is None, "Multiple roots detected, invalid URDF."
981  root = link
982  assert root is not None, "No roots detected, invalid URDF."
983  return root
984 
985  def to_xml(self, orderbytree=False, orderbytype=False):
986  doc = Document()
987  root = doc.createElement("robot")
988  doc.appendChild(root)
989  root.setAttribute("name", self.name)
990 
991  baselink = self.parent_map
992  if orderbytree:
993  # Walk child map sequentially and export
994  pass
995  if orderbytype:
996  pass
997 
998  for element in self.elements:
999  root.appendChild(element.to_xml(doc))
1000 
1001  return doc.toprettyxml()
1002 
1003  def write_xml(self, outfile=None):
1004  if outfile is None:
1005  outfile = self.name + '.urdf'
1006 
1007  self.write_reformatted(self.to_xml(), outfile)
1008 
1009  def make_openrave_kinbody(self, doc):
1010  kinbody = doc.createElement("kinbody")
1011  doc.appendChild(kinbody)
1012  kinbody.setAttribute("name", self.name)
1013 
1014  for element in self.elements:
1015  kinbody.appendChild(element.to_openrave_xml(doc))
1016 
1017  # Post-processing to add offsetfrom statements
1018 
1019  for j in self.joints.keys():
1020  for l in kinbody.getElementsByTagName('body'):
1021  if l.getAttribute('name') == self.joints[j].child:
1022  # Add offsetfrom declarration and joint anchor as transform
1023  l.appendChild(create_element(doc, "offsetfrom", self.joints[j].parent))
1024  add_openrave(doc, l, self.joints[j].origin)
1025  break
1026 
1027  # Add adjacencies
1028  for j in self.joints.values():
1029  kinbody.appendChild(create_element(doc, "adjacent", [j.parent, j.child]))
1030 
1031  # Add known extra adjacencies
1032  badjoints = {'LAR': 'LKP', 'LWR': 'LWY', 'LSY': 'LSP', 'LHY': 'LHP',
1033  'RAR': 'RKP', 'RWR': 'RWY', 'RSY': 'RSP', 'RHY': 'RHP',
1034  'NK1': 'Torso'}
1035  for k, v in badjoints.items():
1036  # TODO: search all bodies for above pairs and add extra adjacency tags
1037  b1 = None
1038  b2 = None
1039  for b in kinbody.getElementsByTagName('body'):
1040  if re.search(k, b.getAttribute('name')):
1041  b1 = b.getAttribute('name')
1042  if re.search(v, b.getAttribute('name')):
1043  b2 = b.getAttribute('name')
1044  if b1 and b2:
1045  kinbody.appendChild(create_element(doc, "adjacent", [b1, b2]))
1046 
1047  return kinbody
1048 
1049  def to_openrave_xml(self):
1050  doc = Document()
1051  root = doc.createElement("robot")
1052  doc.appendChild(root)
1053  root.setAttribute("name", self.name)
1054  root.appendChild(self.make_openrave_kinbody(doc))
1055 
1056  return doc.toprettyxml()
1057 
1058  def write_reformatted(self, data, name):
1059  if name is None:
1060  name = self.name
1061  outdata = re.sub(r'\t', ' ', data)
1062  with open(name, 'w+') as f:
1063  f.write(outdata)
1064 
1065  def write_openrave_files(self, outname=None, writerobot=False):
1066  if outname is None:
1067  outname = self.name
1068 
1069  kinfile = outname + '.kinbody.xml'
1070 
1071  if writerobot:
1072  robotfile = outname + '.robot.xml'
1073  doc = Document()
1074  root = doc.createElement("robot")
1075  doc.appendChild(root)
1076  root.setAttribute("name", outname)
1077  kinbody = doc.createElement("kinbody")
1078  root.appendChild(kinbody)
1079  kinbody.setAttribute("name", outname)
1080  kinbody.setAttribute("file", kinfile)
1081  self.write_reformatted(doc.toprettyxml(), robotfile)
1082 
1083  doc2 = Document()
1084  doc2.appendChild(self.make_openrave_kinbody(doc2))
1085 
1086  self.write_reformatted(doc2.toprettyxml(), kinfile)
1087 
1088  def __str__(self):
1089  s = "Name: {0}\n".format(self.name)
1090  s += "\n"
1091  s += "Links:\n"
1092  if len(self.links) == 0:
1093  s += "None\n"
1094  else:
1095  for k, v in self.links.iteritems():
1096  s += "- Link '{0}':\n{1}\n".format(k, reindent(str(v), 1))
1097  s += "\n"
1098  s += "Joints:\n"
1099  if len(self.joints) == 0:
1100  s += "None\n"
1101  else:
1102  for k, v in self.joints.iteritems():
1103  s += "- Joint '{0}':\n{1}\n".format(k, reindent(str(v), 1))
1104  s += "\n"
1105  s += "Materials:\n"
1106  if len(self.materials) == 0:
1107  s += "None\n"
1108  else:
1109  for k, v in self.materials.iteritems():
1110  s += "- Material '{0}':\n{1}\n".format(k, reindent(str(v), 1))
1111 
1112  return s
1113 
1114  def walk_chain(self, link, branchorder=None):
1115  """Walk along the first branch of urdf tree to find last link. Optionally specify which fork to take globally)."""
1116  child = link
1117  if branchorder is None:
1118  branchorder = 0
1119 
1120  while self.child_map in child:
1121  children = self.child_map[link]
1122  l = len(children)
1123  child = children[min(branchorder, l - 1)][1]
1124 
1125  return child
1126 
1127  def rename_link(self, link, newlink):
1128  """Rename a link, updating all internal references to the name, and
1129  removing the old name from the links dict."""
1130  self.links[link].name = newlink
1131  self.links[newlink] = self.links[link]
1132  self.links.pop(link)
1133  for k, v in self.parent_map.items():
1134  if k == link:
1135  self.parent_map[newlink] = v
1136  self.parent_map.pop(k)
1137  k = newlink
1138  if v[0] == link:
1139  new0 = newlink
1140  v = (new0, v[1])
1141  if v[1] == link:
1142  new1 = newlink
1143  v = (v[0], new1)
1144  self.parent_map[k] = v
1145  for k, v in self.child_map.items():
1146  if k == link:
1147  self.child_map[newlink] = v
1148  self.child_map.pop(k)
1149  k = newlink
1150  vnew = []
1151  for el in v:
1152  if el[1] == link:
1153  el = (el[0], newlink)
1154  vnew.append(el)
1155  # print(vnew)
1156  self.child_map[k] = vnew
1157  for n, j in self.joints.items():
1158  if j.parent == link:
1159  j.parent = newlink
1160  if j.child == link:
1161  j.child = newlink
1162  # print(self.child_map)
1163 
1164  def rename_joint(self, joint, newjoint):
1165  """Find a joint and rename it to newjoint, updating all internal
1166  structures and mimic joints with the new name. Removes the old joint
1167  reference from the joints list."""
1168  self.joints[joint].name = newjoint
1169  self.joints[newjoint] = self.joints[joint]
1170  self.joints.pop(joint)
1171  for k, v in self.child_map.items():
1172  vnew = []
1173  for el in v:
1174  if el[0] == joint:
1175  el = (newjoint, el[1])
1176  print(el)
1177  vnew.append(el)
1178  self.child_map[k] = vnew
1179  for k, v in self.parent_map.items():
1180  if v[0] == joint:
1181  v = (newjoint, v[1])
1182  print(el)
1183  self.parent_map[k] = v
1184  for n, j in self.joints.items():
1185  if j.mimic is not None:
1186  j.mimic.joint_name = newjoint if j.mimic.joint_name == joint else j.mimic.joint_name
1187 
1188  def copy_joint(self, joint, f, r):
1189  """Copy and rename a joint and it's parent/child by the f / r strings. Assumes links exist.
1190  Note that it renames the parent and child, so use this with copy_link"""
1191  newjoint = copy.deepcopy(self.joints[joint])
1192  newjoint.name = re.sub(f, r, newjoint.name)
1193  newjoint.parent = re.sub(f, r, newjoint.parent)
1194  newjoint.child = re.sub(f, r, newjoint.child)
1195 
1196  self.add_joint(newjoint)
1197  return newjoint
1198 
1199  def move_chain_with_rottrans(self, root, tip, rpy, xyz, f, r):
1200  """Find and rename a kinematic chain based on the given root and top
1201  names. Renames all links and joints according to find and replace
1202  terms.
1203  """
1204  linkchain = self.get_chain(root, tip, links=True, joints=False)
1205  jointchain = self.get_chain(root, tip, joints=True, links=False)
1206  print(linkchain)
1207  print(jointchain)
1208 
1209  for l in linkchain[1:]:
1210  newlink = re.sub(f, r, l)
1211  self.rename_link(l, newlink)
1212  for j in jointchain:
1213  newname = re.sub(f, r, j)
1214  self.rename_joint(j, newname)
1215  self.joints[newname].origin.position += array(xyz)
1216  self.joints[newname].origin.rotation += array(rpy)
1217  if self.joints[newname].mimic is not None:
1218  self.joints[newname].mimic.joint_name = re.sub(f, r, self.joints[newname].mimic.joint_name)
1219 
1220  def copy_chain_with_rottrans(self, root, tip, rpy, xyz, f, r, mir_ax=None):
1221  """Copy a kinematic chain, renaming joints and links according to a regular expression.
1222 
1223  Note that this is designed to work with the Hubo joint / body
1224  convention, which has an easy pattern for joint and body names. If your
1225  model has joints and links that are not systematically named, this
1226  function won't be much use.
1227  """
1228 
1229  linkchain = self.get_chain(root, tip, links=True, joints=False)
1230  jointchain = self.get_chain(root, tip, joints=True, links=False)
1231  print(linkchain)
1232  print(jointchain)
1233  newjoints = []
1234  newlinks = []
1235  for l in linkchain[1:]:
1236  newlink = copy.deepcopy(self.links[l])
1237  newlink.name = re.sub(f, r, newlink.name)
1238  if newlink.collision is not None:
1239  newlink.collision.geometry.filename = re.sub(f, r, newlink.collision.geometry.filename)
1240  newlink.visual.geometry.filename = re.sub(f, r, newlink.visual.geometry.filename)
1241  self.add_link(newlink)
1242  newlinks.append(newlink)
1243  if mir_ax == 'x':
1244  newlink.inertial.matrix['ixy'] *= -1.
1245  newlink.inertial.matrix['ixz'] *= -1.
1246  newlink.inertial.origin.position[0] *= -1.
1247  if mir_ax == 'y':
1248  newlink.inertial.matrix['ixy'] *= -1.
1249  newlink.inertial.matrix['iyz'] *= -1.
1250  newlink.inertial.origin.position[1] *= -1.
1251  if mir_ax == 'z':
1252  newlink.inertial.matrix['ixz'] *= -1.
1253  newlink.inertial.matrix['iyz'] *= -1.
1254  newlink.inertial.origin.position[2] *= -1.
1255  # Hack to rotate just first joint
1256  for j in jointchain:
1257  newjoints.append(self.copy_joint(j, f, r))
1258  if mir_ax == 'x':
1259  newjoints[-1].origin.position[0] *= -1.0
1260  newjoints[-1].origin.rotation[1] *= -1.0
1261  newjoints[-1].origin.rotation[2] *= -1.0
1262  if mir_ax == 'y':
1263  newjoints[-1].origin.position[1] *= -1.0
1264  newjoints[-1].origin.rotation[0] *= -1.0
1265  newjoints[-1].origin.rotation[2] *= -1.0
1266  if mir_ax == 'z':
1267  newjoints[-1].origin.position[2] *= -1.0
1268  newjoints[-1].origin.rotation[0] *= -1.0
1269  newjoints[-1].origin.rotation[1] *= -1.0
1270 
1271  if mir_ax == 'rotx':
1272  newjoints[0].origin.position[1] *= -1.0
1273 
1274  for j in newjoints:
1275  if j.mimic is not None:
1276  j.mimic.joint_name = re.sub(f, r, j.mimic.joint_name)
1277 
1278  newjoints[0].origin.position += array(xyz)
1279  newjoints[0].origin.rotation += array(rpy)
1280 
1281  def fix_mesh_case(self):
1282  for l in self.links:
1283  fname = l.collision.geometry.filename
1284  l.collision.geometry.filename = re.sub(r'\.[Ss][Tt][Ll]', '.stl', fname)
1285  # TODO: merge function to tie two chains together from disparate models
1286 
1287  def update_mesh_paths(self, package_name):
1288  """Search and replace package paths in urdf with chosen package name"""
1289  for n, l in self.links.items():
1290  # TODO: check if mesh
1291  for g in [l.collision.geometry, l.visual.geometry]:
1292  # save STL file name only
1293  meshfile = g.filename.split('/')[-1]
1294  newpath = [package_name, 'meshes', meshfile]
1295  cleanpath = re.sub('/+', '/', '/'.join(newpath))
1296  g.filename = 'package://' + cleanpath
1297  l.collision.geometry.filename = re.sub('Body', 'convhull', l.collision.geometry.filename)
1298 
1299  def apply_default_limits(self, effort, vel, lower, upper, mask=None):
1300  """Apply default limits to all joints and convert continous joints to revolute. Ignores fixed and other joint types."""
1301  for n, j in self.joints.items():
1302  if mask is None or re.search(mask, n):
1303  if j.joint_type == Joint.CONTINUOUS or j.joint_type == Joint.REVOLUTE:
1304  j.limits = JointLimit(effort, vel, lower, upper)
1305  j.joint_type = Joint.REVOLUTE
1306 
1307 if __name__ == '__main__':
1308  # try:
1309  # from openhubo import startup
1310  # except ImportError:
1311  # pass
1312 
1313  try:
1314  filename = sys.argv[1]
1315  except IndexError:
1316  print('Please supply a URDF filename to convert!')
1317 
1318  try:
1319  outname = sys.argv[2]
1320  except IndexError:
1321  outname = None
1322 
1323  model = URDF.load_xml_file(filename)
1324 
1325  model.write_openrave_files(outname)
def __str__(self)
Definition: urdf.py:154
def to_xml(self, doc)
Definition: urdf.py:34
def to_xml(self, doc)
Definition: urdf.py:777
def __init__(self, rising=None, falling=None)
Definition: urdf.py:464
def get_chain(self, root, tip, joints=True, links=True, fixed=True)
Definition: urdf.py:959
def walk_chain(self, link, branchorder=None)
Definition: urdf.py:1114
def __str__(self)
Definition: urdf.py:1088
def parse(node, verbose=True)
Definition: urdf.py:342
def get_from_table(self, node)
Definition: urdf.py:511
def to_openrave_xml(self, doc)
Definition: urdf.py:149
def parse(node)
Definition: urdf.py:195
def to_openrave_xml(self, doc)
Definition: urdf.py:483
def __init__(self, joint_name, multiplier=None, offset=None)
Definition: urdf.py:544
def short(doc, name, key, value)
Definition: gazeboUrdf.py:97
def parse(node)
Definition: urdf.py:222
def __str__(self)
Definition: urdf.py:211
def to_xml(self, doc)
Definition: urdf.py:232
def add(doc, base, element)
Definition: gazeboUrdf.py:39
def write_openrave_files(self, outname=None, writerobot=False)
Definition: urdf.py:1065
def __init__(self, geometry=None, material=None, origin=None)
Definition: urdf.py:757
def to_xml(self, doc)
Definition: urdf.py:142
def to_openrave_xml(self, doc)
Definition: urdf.py:97
def __init__(self, radius=0.0)
Definition: urdf.py:191
def __init__(self, position=None, rotation=None)
Definition: urdf.py:676
def parse(node)
Definition: urdf.py:58
def to_openrave_xml(self, doc)
Definition: urdf.py:697
def __str__(self)
Definition: urdf.py:716
def parse(node)
Definition: urdf.py:681
def to_string(data=None)
Definition: gazeboUrdf.py:62
def __init__(self, dims=None)
Definition: urdf.py:131
def apply_default_limits(self, effort, vel, lower, upper, mask=None)
Definition: urdf.py:1299
def to_xml(self, doc)
Definition: urdf.py:652
def update_mesh_paths(self, package_name)
Definition: urdf.py:1287
def __init__(self, damping=None, friction=None)
Definition: urdf.py:78
def copy_joint(self, joint, f, r)
Definition: urdf.py:1188
def add_joint(self, joint)
Definition: urdf.py:934
def to_xml(self, doc)
Definition: urdf.py:814
def __str__(self)
Definition: urdf.py:71
def to_openrave_xml(self, doc)
Definition: urdf.py:40
def to_openrave_xml(self, doc)
Definition: urdf.py:241
def __str__(self)
Definition: urdf.py:250
def add_material(self, material)
Definition: urdf.py:944
def __init__(self, r=0.0, g=0.0, b=0.0, a=0.0)
Definition: urdf.py:54
def to_xml(self, doc)
Definition: urdf.py:199
def add_openrave(doc, base, element)
Definition: gazeboUrdf.py:45
def to_openrave_xml(self, doc)
Definition: urdf.py:294
def to_xml(self, doc)
Definition: urdf.py:369
def to_openrave_xml(self, doc)
Definition: urdf.py:68
def copy_chain_with_rottrans(self, root, tip, rpy, xyz, f, r, mir_ax=None)
Definition: urdf.py:1220
def parse(node, verbose=True)
Definition: urdf.py:23
def parse_xml_string(xml_string, verbose=True)
Definition: urdf.py:888
def parse(node, verbose=True)
Definition: urdf.py:801
def __init__(self, name=None, hardwareInterface=None, mechanicalReduction=1)
Definition: urdf.py:795
def __str__(self)
Definition: urdf.py:784
def load_from_parameter_server(key='robot_description', verbose=True)
Definition: urdf.py:920
def write_xml(self, outfile=None)
Definition: urdf.py:1003
def to_xml(self, doc)
Definition: urdf.py:63
def __init__(self, name=None, color=None, texture=None)
Definition: urdf.py:631
def rename_joint(self, joint, newjoint)
Definition: urdf.py:1164
def parse(node, verbose=True)
Definition: urdf.py:111
def get_root(self)
Definition: urdf.py:976
def __init__(self, filename=None, scale=1)
Definition: urdf.py:217
def to_xml(self, doc)
Definition: urdf.py:281
def to_openrave_xml(self, doc)
Definition: urdf.py:386
def to_openrave_xml(self)
Definition: urdf.py:1049
def parse(node, verbose=True)
Definition: urdf.py:637
def __init__(self, velocity, position=None, lower=None, upper=None)
Definition: urdf.py:722
def to_xml(self, orderbytree=False, orderbytype=False)
Definition: urdf.py:985
def __init__(self, geometry=None, origin=None)
Definition: urdf.py:18
def write_reformatted(self, data, name)
Definition: urdf.py:1058
def __init__(self)
Definition: urdf.py:107
def fix_mesh_case(self)
Definition: urdf.py:1281
def __init__(self, name=None, type=None, joint=None, actuator=None)
Definition: urdf.py:830
def rename_link(self, link, newlink)
Definition: urdf.py:1127
def to_xml(self, doc)
Definition: urdf.py:91
def move_chain_with_rottrans(self, root, tip, rpy, xyz, f, r)
Definition: urdf.py:1199
def parse(node, verbose=True)
Definition: urdf.py:837
def parse(node, verbose=True)
Definition: urdf.py:763
def add_link(self, link)
Definition: urdf.py:930
def __init__(self, effort, velocity, lower=None, upper=None)
Definition: urdf.py:495
def to_openrave_xml(self, doc)
Definition: urdf.py:528
def set_attribute(node, name, value)
Definition: gazeboUrdf.py:85
def to_xml(self, doc)
Definition: urdf.py:691
def set_content(doc, node, data)
Definition: gazeboUrdf.py:90
def make_openrave_kinbody(self, doc)
Definition: urdf.py:1009
def reindent(s, numSpaces)
Definition: gazeboUrdf.py:31
def to_xml(self, doc)
Definition: urdf.py:558
def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0, mass=0.0, origin=None)
Definition: urdf.py:257
def to_xml(self, doc)
Definition: urdf.py:851
def parse(node)
Definition: urdf.py:138
def load_xml_file(filename, verbose=True)
Definition: urdf.py:914
def __init__(self, radius=0.0, length=0.0)
Definition: urdf.py:160
def to_xml(self, doc)
Definition: urdf.py:170
def __init__(self, name="")
Definition: urdf.py:877
def create_element(doc, name, contents=None, key=None, value=None)
Definition: gazeboUrdf.py:103
def to_openrave_xml(self, doc)
Definition: urdf.py:206
def __init__(self, name, parent, child, joint_type, axis=None, origin=None, limits=None, dynamics=None, safety=None, calibration=None, mimic=None)
Definition: urdf.py:328
def add_gazebo(self, gazebo)
Definition: urdf.py:951
def to_openrave_xml(self, doc)
Definition: urdf.py:178
def to_xml(self, doc)
Definition: urdf.py:520
def __str__(self)
Definition: urdf.py:424


naoqi_tools
Author(s): Mikael Arguedas
autogenerated on Thu Jul 16 2020 03:18:37