urdf.py
Go to the documentation of this file.
3 
4 # Add a 'namespace' for names to avoid a conflict between URDF and SDF?
5 # A type registry? How to scope that? Just make a 'global' type pointer?
6 # Or just qualify names? urdf.geometric, sdf.geometric
7 
8 xmlr.start_namespace('urdf')
9 
10 xmlr.add_type('element_link', xmlr.SimpleElementType('link', str))
11 xmlr.add_type('element_xyz', xmlr.SimpleElementType('xyz', 'vector3'))
12 
13 verbose = True
14 
15 
16 class Pose(xmlr.Object):
17  def __init__(self, xyz=None, rpy=None):
18  self.xyz = xyz
19  self.rpy = rpy
20 
21  def check_valid(self):
22  assert (self.xyz is None or len(self.xyz) == 3) and \
23  (self.rpy is None or len(self.rpy) == 3)
24 
25  # Aliases for backwards compatibility
26  @property
27  def rotation(self): return self.rpy
28 
29  @rotation.setter
30  def rotation(self, value): self.rpy = value
31 
32  @property
33  def position(self): return self.xyz
34 
35  @position.setter
36  def position(self, value): self.xyz = value
37 
38 
39 xmlr.reflect(Pose, tag='origin', params=[
40  xmlr.Attribute('xyz', 'vector3', False, default=[0, 0, 0]),
41  xmlr.Attribute('rpy', 'vector3', False, default=[0, 0, 0])
42 ])
43 
44 
45 # Common stuff
46 name_attribute = xmlr.Attribute('name', str)
47 origin_element = xmlr.Element('origin', Pose, False)
48 
49 
50 class Color(xmlr.Object):
51  def __init__(self, *args):
52  # What about named colors?
53  count = len(args)
54  if count == 4 or count == 3:
55  self.rgba = args
56  elif count == 1:
57  self.rgba = args[0]
58  elif count == 0:
59  self.rgba = None
60  if self.rgba is not None:
61  if len(self.rgba) == 3:
62  self.rgba += [1.]
63  if len(self.rgba) != 4:
64  raise Exception('Invalid color argument count')
65 
66 
67 xmlr.reflect(Color, tag='color', params=[
68  xmlr.Attribute('rgba', 'vector4')
69 ])
70 
71 
72 class JointDynamics(xmlr.Object):
73  def __init__(self, damping=None, friction=None):
74  self.damping = damping
75  self.friction = friction
76 
77 
78 xmlr.reflect(JointDynamics, tag='dynamics', params=[
79  xmlr.Attribute('damping', float, False),
80  xmlr.Attribute('friction', float, False)
81 ])
82 
83 
84 class Box(xmlr.Object):
85  def __init__(self, size=None):
86  self.size = size
87 
88 
89 xmlr.reflect(Box, tag='box', params=[
90  xmlr.Attribute('size', 'vector3')
91 ])
92 
93 
94 class Cylinder(xmlr.Object):
95  def __init__(self, radius=0.0, length=0.0):
96  self.radius = radius
97  self.length = length
98 
99 
100 xmlr.reflect(Cylinder, tag='cylinder', params=[
101  xmlr.Attribute('radius', float),
102  xmlr.Attribute('length', float)
103 ])
104 
105 
106 class Sphere(xmlr.Object):
107  def __init__(self, radius=0.0):
108  self.radius = radius
109 
110 
111 xmlr.reflect(Sphere, tag='sphere', params=[
112  xmlr.Attribute('radius', float)
113 ])
114 
115 
116 class Mesh(xmlr.Object):
117  def __init__(self, filename=None, scale=None):
118  self.filename = filename
119  self.scale = scale
120 
121 
122 xmlr.reflect(Mesh, tag='mesh', params=[
123  xmlr.Attribute('filename', str),
124  xmlr.Attribute('scale', 'vector3', required=False)
125 ])
126 
127 
128 class GeometricType(xmlr.ValueType):
129  def __init__(self):
130  self.factory = xmlr.FactoryType('geometric', {
131  'box': Box,
132  'cylinder': Cylinder,
133  'sphere': Sphere,
134  'mesh': Mesh
135  })
136 
137  def from_xml(self, node, path):
138  children = xml_children(node)
139  assert len(children) == 1, 'One element only for geometric'
140  return self.factory.from_xml(children[0], path=path)
141 
142  def write_xml(self, node, obj):
143  name = self.factory.get_name(obj)
144  child = node_add(node, name)
145  obj.write_xml(child)
146 
147 
148 xmlr.add_type('geometric', GeometricType())
149 
150 
151 class Collision(xmlr.Object):
152  def __init__(self, geometry=None, origin=None, name=None):
153  self.geometry = geometry
154  self.name = name
155  self.origin = origin
156 
157 
158 xmlr.reflect(Collision, tag='collision', params=[
159  xmlr.Attribute('name', str, False),
160  origin_element,
161  xmlr.Element('geometry', 'geometric')
162 ])
163 
164 
165 class Texture(xmlr.Object):
166  def __init__(self, filename=None):
167  self.filename = filename
168 
169 
170 xmlr.reflect(Texture, tag='texture', params=[
171  xmlr.Attribute('filename', str)
172 ])
173 
174 
175 class Material(xmlr.Object):
176  def __init__(self, name=None, color=None, texture=None):
177  self.name = name
178  self.color = color
179  self.texture = texture
180 
181  def check_valid(self):
182  if self.color is None and self.texture is None:
183  xmlr.on_error("Material has neither a color nor texture.")
184 
185 
186 xmlr.reflect(Material, tag='material', params=[
187  name_attribute,
188  xmlr.Element('color', Color, False),
189  xmlr.Element('texture', Texture, False)
190 ])
191 
192 
194  def check_valid(self):
195  pass
196 
197 
198 class Visual(xmlr.Object):
199  def __init__(self, geometry=None, material=None, origin=None, name=None):
200  self.geometry = geometry
201  self.material = material
202  self.name = name
203  self.origin = origin
204 
205 
206 xmlr.reflect(Visual, tag='visual', params=[
207  xmlr.Attribute('name', str, False),
208  origin_element,
209  xmlr.Element('geometry', 'geometric'),
210  xmlr.Element('material', LinkMaterial, False)
211 ])
212 
213 
214 class Inertia(xmlr.Object):
215  KEYS = ['ixx', 'ixy', 'ixz', 'iyy', 'iyz', 'izz']
216 
217  def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0):
218  self.ixx = ixx
219  self.ixy = ixy
220  self.ixz = ixz
221  self.iyy = iyy
222  self.iyz = iyz
223  self.izz = izz
224 
225  def to_matrix(self):
226  return [
227  [self.ixx, self.ixy, self.ixz],
228  [self.ixy, self.iyy, self.iyz],
229  [self.ixz, self.iyz, self.izz]]
230 
231 
232 xmlr.reflect(Inertia, tag='inertia',
233  params=[xmlr.Attribute(key, float) for key in Inertia.KEYS])
234 
235 
236 class Inertial(xmlr.Object):
237  def __init__(self, mass=0.0, inertia=None, origin=None):
238  self.mass = mass
239  self.inertia = inertia
240  self.origin = origin
241 
242 
243 xmlr.reflect(Inertial, tag='inertial', params=[
244  origin_element,
245  xmlr.Element('mass', 'element_value'),
246  xmlr.Element('inertia', Inertia, False)
247 ])
248 
249 
250 # FIXME: we are missing the reference position here.
251 class JointCalibration(xmlr.Object):
252  def __init__(self, rising=None, falling=None):
253  self.rising = rising
254  self.falling = falling
255 
256 
257 xmlr.reflect(JointCalibration, tag='calibration', params=[
258  xmlr.Attribute('rising', float, False, 0),
259  xmlr.Attribute('falling', float, False, 0)
260 ])
261 
262 
263 class JointLimit(xmlr.Object):
264  def __init__(self, effort=None, velocity=None, lower=None, upper=None):
265  self.effort = effort
266  self.velocity = velocity
267  self.lower = lower
268  self.upper = upper
269 
270 
271 xmlr.reflect(JointLimit, tag='limit', params=[
272  xmlr.Attribute('effort', float),
273  xmlr.Attribute('lower', float, False, 0),
274  xmlr.Attribute('upper', float, False, 0),
275  xmlr.Attribute('velocity', float)
276 ])
277 
278 # FIXME: we are missing __str__ here.
279 
280 
281 class JointMimic(xmlr.Object):
282  def __init__(self, joint_name=None, multiplier=None, offset=None):
283  self.joint = joint_name
284  self.multiplier = multiplier
285  self.offset = offset
286 
287 
288 xmlr.reflect(JointMimic, tag='mimic', params=[
289  xmlr.Attribute('joint', str),
290  xmlr.Attribute('multiplier', float, False),
291  xmlr.Attribute('offset', float, False)
292 ])
293 
294 
295 class SafetyController(xmlr.Object):
296  def __init__(self, velocity=None, position=None, lower=None, upper=None):
297  self.k_velocity = velocity
298  self.k_position = position
299  self.soft_lower_limit = lower
300  self.soft_upper_limit = upper
301 
302 
303 xmlr.reflect(SafetyController, tag='safety_controller', params=[
304  xmlr.Attribute('k_velocity', float),
305  xmlr.Attribute('k_position', float, False, 0),
306  xmlr.Attribute('soft_lower_limit', float, False, 0),
307  xmlr.Attribute('soft_upper_limit', float, False, 0)
308 ])
309 
310 
311 class Joint(xmlr.Object):
312  TYPES = ['unknown', 'revolute', 'continuous', 'prismatic',
313  'floating', 'planar', 'fixed']
314 
315  def __init__(self, name=None, parent=None, child=None, joint_type=None,
316  axis=None, origin=None,
317  limit=None, dynamics=None, safety_controller=None,
318  calibration=None, mimic=None):
319  self.name = name
320  self.parent = parent
321  self.child = child
322  self.type = joint_type
323  self.axis = axis
324  self.origin = origin
325  self.limit = limit
326  self.dynamics = dynamics
327  self.safety_controller = safety_controller
328  self.calibration = calibration
329  self.mimic = mimic
330 
331  def check_valid(self):
332  assert self.type in self.TYPES, "Invalid joint type: {}".format(self.type) # noqa
333 
334  # Aliases
335  @property
336  def joint_type(self): return self.type
337 
338  @joint_type.setter
339  def joint_type(self, value): self.type = value
340 
341 xmlr.reflect(Joint, tag='joint', params=[
342  name_attribute,
343  xmlr.Attribute('type', str),
344  origin_element,
345  xmlr.Element('axis', 'element_xyz', False),
346  xmlr.Element('parent', 'element_link'),
347  xmlr.Element('child', 'element_link'),
348  xmlr.Element('limit', JointLimit, False),
349  xmlr.Element('dynamics', JointDynamics, False),
350  xmlr.Element('safety_controller', SafetyController, False),
351  xmlr.Element('calibration', JointCalibration, False),
352  xmlr.Element('mimic', JointMimic, False),
353 ])
354 
355 
356 class Link(xmlr.Object):
357  def __init__(self, name=None, visual=None, inertial=None, collision=None,
358  origin=None):
359  self.aggregate_init()
360  self.name = name
361  self.visuals = []
362  if visual:
363  self.visual = visual
364  self.inertial = inertial
365  self.collisions = []
366  if collision:
367  self.collision = collision
368  self.origin = origin
369 
370  def __get_visual(self):
371  """Return the first visual or None."""
372  if self.visuals:
373  return self.visuals[0]
374 
375  def __set_visual(self, visual):
376  """Set the first visual."""
377  if self.visuals:
378  self.visuals[0] = visual
379  else:
380  self.visuals.append(visual)
381  if visual:
382  self.add_aggregate('visual', visual)
383 
384  def __get_collision(self):
385  """Return the first collision or None."""
386  if self.collisions:
387  return self.collisions[0]
388 
389  def __set_collision(self, collision):
390  """Set the first collision."""
391  if self.collisions:
392  self.collisions[0] = collision
393  else:
394  self.collisions.append(collision)
395  if collision:
396  self.add_aggregate('collision', collision)
397 
398  # Properties for backwards compatibility
399  visual = property(__get_visual, __set_visual)
400  collision = property(__get_collision, __set_collision)
401 
402 
403 xmlr.reflect(Link, tag='link', params=[
404  name_attribute,
405  origin_element,
406  xmlr.AggregateElement('visual', Visual),
407  xmlr.AggregateElement('collision', Collision),
408  xmlr.Element('inertial', Inertial, False),
409 ])
410 
411 
412 class PR2Transmission(xmlr.Object):
413  def __init__(self, name=None, joint=None, actuator=None, type=None,
414  mechanicalReduction=1):
415  self.name = name
416  self.type = type
417  self.joint = joint
418  self.actuator = actuator
419  self.mechanicalReduction = mechanicalReduction
420 
421 
422 xmlr.reflect(PR2Transmission, tag='pr2_transmission', params=[
423  name_attribute,
424  xmlr.Attribute('type', str),
425  xmlr.Element('joint', 'element_name'),
426  xmlr.Element('actuator', 'element_name'),
427  xmlr.Element('mechanicalReduction', float)
428 ])
429 
430 
431 class Actuator(xmlr.Object):
432  def __init__(self, name=None, mechanicalReduction=1):
433  self.name = name
435 
436 
437 xmlr.reflect(Actuator, tag='actuator', params=[
438  name_attribute,
439  xmlr.Element('mechanicalReduction', float, required=False)
440 ])
441 
442 
443 class TransmissionJoint(xmlr.Object):
444  def __init__(self, name=None):
445  self.aggregate_init()
446  self.name = name
448 
449  def check_valid(self):
450  assert len(self.hardwareInterfaces) > 0, "no hardwareInterface defined"
451 
452 
453 xmlr.reflect(TransmissionJoint, tag='joint', params=[
454  name_attribute,
455  xmlr.AggregateElement('hardwareInterface', str),
456 ])
457 
458 
459 class Transmission(xmlr.Object):
460  """ New format: http://wiki.ros.org/urdf/XML/Transmission """
461 
462  def __init__(self, name=None):
463  self.aggregate_init()
464  self.name = name
465  self.joints = []
466  self.actuators = []
467 
468  def check_valid(self):
469  assert len(self.joints) > 0, "no joint defined"
470  assert len(self.actuators) > 0, "no actuator defined"
471 
472 
473 xmlr.reflect(Transmission, tag='new_transmission', params=[
474  name_attribute,
475  xmlr.Element('type', str),
476  xmlr.AggregateElement('joint', TransmissionJoint),
477  xmlr.AggregateElement('actuator', Actuator)
478 ])
479 
480 xmlr.add_type('transmission',
481  xmlr.DuckTypedFactory('transmission',
482  [Transmission, PR2Transmission]))
483 
484 
485 class Robot(xmlr.Object):
486  SUPPORTED_VERSIONS = ["1.0"]
487 
488  def __init__(self, name=None, version="1.0"):
489  self.aggregate_init()
490 
491  self.name = name
492  if version not in self.SUPPORTED_VERSIONS:
493  raise ValueError("Invalid version; only %s is supported" % (','.join(self.SUPPORTED_VERSIONS)))
494 
495  self.version = version
496  self.joints = []
497  self.links = []
498  self.materials = []
499  self.gazebos = []
500  self.transmissions = []
501 
502  self.joint_map = {}
503  self.link_map = {}
504 
505  self.parent_map = {}
506  self.child_map = {}
507 
508  def add_aggregate(self, typeName, elem):
509  xmlr.Object.add_aggregate(self, typeName, elem)
510 
511  if typeName == 'joint':
512  joint = elem
513  self.joint_map[joint.name] = joint
514  self.parent_map[joint.child] = (joint.name, joint.parent)
515  if joint.parent in self.child_map:
516  self.child_map[joint.parent].append((joint.name, joint.child))
517  else:
518  self.child_map[joint.parent] = [(joint.name, joint.child)]
519  elif typeName == 'link':
520  link = elem
521  self.link_map[link.name] = link
522 
523  def add_link(self, link):
524  self.add_aggregate('link', link)
525 
526  def add_joint(self, joint):
527  self.add_aggregate('joint', joint)
528 
529  def get_chain(self, root, tip, joints=True, links=True, fixed=True):
530  chain = []
531  if links:
532  chain.append(tip)
533  link = tip
534  while link != root:
535  (joint, parent) = self.parent_map[link]
536  if joints:
537  if fixed or self.joint_map[joint].joint_type != 'fixed':
538  chain.append(joint)
539  if links:
540  chain.append(parent)
541  link = parent
542  chain.reverse()
543  return chain
544 
545  def get_root(self):
546  root = None
547  for link in self.link_map:
548  if link not in self.parent_map:
549  assert root is None, "Multiple roots detected, invalid URDF."
550  root = link
551  assert root is not None, "No roots detected, invalid URDF."
552  return root
553 
554  def post_read_xml(self):
555  if self.version is None:
556  self.version = "1.0"
557 
558  split = self.version.split(".")
559  if len(split) != 2:
560  raise ValueError("The version attribute should be in the form 'x.y'")
561 
562  if split[0] == '' or split[1] == '':
563  raise ValueError("Empty major or minor number is not allowed")
564 
565  if int(split[0]) < 0 or int(split[1]) < 0:
566  raise ValueError("Version number must be positive")
567 
568  if self.version not in self.SUPPORTED_VERSIONS:
569  raise ValueError("Invalid version; only %s is supported" % (','.join(self.SUPPORTED_VERSIONS)))
570 
571  @classmethod
572  def from_parameter_server(cls, key='robot_description'):
573  """
574  Retrieve the robot model on the parameter server
575  and parse it to create a URDF robot structure.
576 
577  Warning: this requires roscore to be running.
578  """
579  # Could move this into xml_reflection
580  import rospy
581  return cls.from_xml_string(rospy.get_param(key))
582 
583 
584 xmlr.reflect(Robot, tag='robot', params=[
585  xmlr.Attribute('name', str),
586  xmlr.Attribute('version', str, False),
587  xmlr.AggregateElement('link', Link),
588  xmlr.AggregateElement('joint', Joint),
589  xmlr.AggregateElement('gazebo', xmlr.RawType()),
590  xmlr.AggregateElement('transmission', 'transmission'),
591  xmlr.AggregateElement('material', Material)
592 ])
593 
594 # Make an alias
595 URDF = Robot
596 
597 xmlr.end_namespace()
def __init__(self, name=None)
Definition: urdf.py:444
def from_parameter_server(cls, key='robot_description')
Definition: urdf.py:572
def position(self)
Definition: urdf.py:33
def check_valid(self)
Definition: urdf.py:21
def add_aggregate(self, typeName, elem)
Definition: urdf.py:508
def add_joint(self, joint)
Definition: urdf.py:526
def __init__(self, xyz=None, rpy=None)
Definition: urdf.py:17
def check_valid(self)
Definition: urdf.py:331
def __init__(self, name=None, parent=None, child=None, joint_type=None, axis=None, origin=None, limit=None, dynamics=None, safety_controller=None, calibration=None, mimic=None)
Definition: urdf.py:318
def __init__(self, joint_name=None, multiplier=None, offset=None)
Definition: urdf.py:282
def __init__(self, geometry=None, material=None, origin=None, name=None)
Definition: urdf.py:199
def __init__(self, size=None)
Definition: urdf.py:85
def __init__(self, radius=0.0)
Definition: urdf.py:107
def get_chain(self, root, tip, joints=True, links=True, fixed=True)
Definition: urdf.py:529
def rotation(self)
Definition: urdf.py:27
def __init__(self, name=None, joint=None, actuator=None, type=None, mechanicalReduction=1)
Definition: urdf.py:414
def __init__(self, effort=None, velocity=None, lower=None, upper=None)
Definition: urdf.py:264
def __init__(self, name=None)
Definition: urdf.py:462
def from_xml(self, node, path)
Definition: urdf.py:137
def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0)
Definition: urdf.py:217
def __init__(self, name=None, mechanicalReduction=1)
Definition: urdf.py:432
def __init__(self, velocity=None, position=None, lower=None, upper=None)
Definition: urdf.py:296
def joint_type(self)
Definition: urdf.py:336
def __init__(self, mass=0.0, inertia=None, origin=None)
Definition: urdf.py:237
def __init__(self, name=None, color=None, texture=None)
Definition: urdf.py:176
def __init__(self, geometry=None, origin=None, name=None)
Definition: urdf.py:152
def __init__(self, filename=None, scale=None)
Definition: urdf.py:117
def post_read_xml(self)
Definition: urdf.py:554
def __init__(self, name=None, version="1.0")
Definition: urdf.py:488
def __init__(self, radius=0.0, length=0.0)
Definition: urdf.py:95
def write_xml(self, node, obj)
Definition: urdf.py:142
def __init__(self, rising=None, falling=None)
Definition: urdf.py:252
def __init__(self, damping=None, friction=None)
Definition: urdf.py:73
def __init__(self, args)
Definition: urdf.py:51
def add_link(self, link)
Definition: urdf.py:523
def __init__(self, filename=None)
Definition: urdf.py:166
def get_root(self)
Definition: urdf.py:545


urdfdom_py
Author(s): Thomas Moulard, David Lu, Kelsey Hawkins, Antonio El Khoury, Eric Cousineau, Ioan Sucan , Jackie Kay
autogenerated on Mon Feb 28 2022 23:58:25