1 import string
2 import rospy
3 import xml.dom.minidom
4 from xml.dom.minidom import Document
7 """Reindent a string for tree structure pretty printing."""
8 s = string.split(s, '\n')
9 s = [(numSpaces * ' ') + line for line in s]
10 s = string.join(s, '\n')
11 return s
12
13 -def add(doc, base, element):
14 if element is not None:
15 base.appendChild( element.to_xml(doc) )
16
18 return "{0}".format(x).rstrip('.')
19
21 if value is None:
22 return
23 if type([]) == type(value) or type(()) == type(value):
24 value = " ".join( [pfloat(a) for a in value] )
25 elif type(value) == type(0.0):
26 value = pfloat(value)
27 elif type(value) != type(''):
28 value = str(value)
29 node.setAttribute(name, value)
30
31 -def short(doc, name, key, value):
32 element = doc.createElement(name)
33 set_attribute(element, key, value)
34 return element
35
37 children = []
38 for child in node.childNodes:
39 if child.nodeType is node.TEXT_NODE \
40 or child.nodeType is node.COMMENT_NODE:
41 continue
42 else:
43 children.append(child)
44 return children
45
47 - def __init__(self, geometry=None, origin=None):
48 self.geometry = geometry
49 self.origin = origin
50
51 @staticmethod
52 - def parse(node, verbose=True):
53 c = Collision()
54 for child in children(node):
55 if child.localName == 'geometry':
56 c.geometry = Geometry.parse(child, verbose)
57 elif child.localName == 'origin':
58 c.origin = Pose.parse(child)
59 else:
60 if verbose:
61 rospy.logwarn("Unknown collision element '%s'"%child.localName)
62 return c
63
65 xml = doc.createElement("collision")
66 add(doc, xml, self.geometry)
67 add(doc, xml, self.origin)
68 return xml
69
71 s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
72 s += "Geometry:\n{0}\n".format(reindent(str(self.geometry), 1))
73 return s
74
76 - def __init__(self, r=0.0, g=0.0, b=0.0, a=0.0):
78
79 @staticmethod
81 rgba = node.getAttribute("rgba").split()
82 (r,g,b,a) = [ float(x) for x in rgba ]
83 return Color(r,g,b,a)
84
86 xml = doc.createElement("color")
87 set_attribute(xml, "rgba", self.rgba)
88 return xml
89
91 return "r: {0}, g: {1}, b: {2}, a: {3},".format(
92 self.r, self.g, self.b, self.a)
93
95 - def __init__(self, damping=None, friction=None):
96 self.damping = damping
97 self.friction = friction
98
99 @staticmethod
101 d = Dynamics()
102 if node.hasAttribute('damping'):
103 d.damping = node.getAttribute('damping')
104 if node.hasAttribute('friction'):
105 d.friction = node.getAttribute('friction')
106 return d
107
109 xml = doc.createElement('dynamics')
110 set_attribute(xml, 'damping', self.damping)
111 set_attribute(xml, 'friction', self.friction)
112 return xml
113
114
116 return "Damping: {0}\nFriction: {1}\n".format(self.damping,
117 self.friction)
118
122
123 @staticmethod
124 - def parse(node, verbose=True):
125 shape = children(node)[0]
126 if shape.localName=='box':
127 return Box.parse(shape)
128 elif shape.localName=='cylinder':
129 return Cylinder.parse(shape)
130 elif shape.localName=='sphere':
131 return Sphere.parse(shape)
132 elif shape.localName=='mesh':
133 return Mesh.parse(shape)
134 else:
135 if verbose:
136 rospy.logwarn("Unknown shape %s"%child.localName)
137
139 return "Geometry abstract class"
140
141 -class Box(Geometry):
143 if dims is None:
144 self.dims = None
145 else:
146 self.dims = (dims[0], dims[1], dims[2])
147
148 @staticmethod
150 dims = node.getAttribute('size').split()
151 return Box([float(a) for a in dims])
152
154 xml = doc.createElement("box")
155 set_attribute(xml, "size", self.dims)
156 geom = doc.createElement('geometry')
157 geom.appendChild(xml)
158 return geom
159
161 return "Dimension: {0}".format(self.dims)
162
165 - def __init__(self, radius=0.0, length=0.0):
166 self.radius = radius
167 self.length = length
168
169 @staticmethod
171 r = node.getAttribute('radius')
172 l = node.getAttribute('length')
173 return Cylinder(float(r), float(l))
174
176 xml = doc.createElement("cylinder")
177 set_attribute(xml, "radius", self.radius)
178 set_attribute(xml, "length", self.length)
179 geom = doc.createElement('geometry')
180 geom.appendChild(xml)
181 return geom
182
184 return "Radius: {0}\nLength: {1}".format(self.radius,
185 self.length)
186
190
191 @staticmethod
193 r = node.getAttribute('radius')
194 return Sphere(float(r))
195
197 xml = doc.createElement("sphere")
198 set_attribute(xml, "radius", self.radius)
199 geom = doc.createElement('geometry')
200 geom.appendChild(xml)
201 return geom
202
204 return "Radius: {0}".format(self.radius)
205
206
207 -class Mesh(Geometry):
208 - def __init__(self, filename=None, scale=None):
209 self.filename = filename
210 self.scale = scale
211
212 @staticmethod
214 fn = node.getAttribute('filename')
215 s = node.getAttribute('scale')
216 if s == "":
217 s = None
218 else:
219 xyz = node.getAttribute('scale').split()
220 scale = map(float, xyz)
221 return Mesh(fn, s)
222
224 xml = doc.createElement("mesh")
225 set_attribute(xml, "filename", self.filename)
226 set_attribute(xml, "scale", self.scale)
227 geom = doc.createElement('geometry')
228 geom.appendChild(xml)
229 return geom
230
232 return "Filename: {0}\nScale: {1}".format(self.filename, self.scale)
233
236 - def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0,
237 mass=0.0, origin=None):
238 self.matrix = {}
239 self.matrix['ixx'] = ixx
240 self.matrix['ixy'] = ixy
241 self.matrix['ixz'] = ixz
242 self.matrix['iyy'] = iyy
243 self.matrix['iyz'] = iyz
244 self.matrix['izz'] = izz
245 self.mass = mass
246 self.origin = origin
247
248 @staticmethod
250 inert = Inertial()
251 for child in children(node):
252 if child.localName=='inertia':
253 for v in ['ixx', 'ixy', 'ixz', 'iyy', 'iyz', 'izz']:
254 inert.matrix[v] = float(child.getAttribute(v))
255 elif child.localName=='mass':
256 inert.mass = float(child.getAttribute('value'))
257 elif child.localName == 'origin':
258 inert.origin = Pose.parse(child)
259 return inert
260
262 xml = doc.createElement("inertial")
263
264 xml.appendChild(short(doc, "mass", "value", self.mass))
265
266 inertia = doc.createElement("inertia")
267 for (n,v) in self.matrix.items():
268 set_attribute(inertia, n, v)
269 xml.appendChild(inertia)
270
271 add(doc, xml, self.origin)
272 return xml
273
275 s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
276 s += "Mass: {0}\n".format(self.mass)
277 s += "ixx: {0}\n".format(self.matrix['ixx'])
278 s += "ixy: {0}\n".format(self.matrix['ixy'])
279 s += "ixz: {0}\n".format(self.matrix['ixz'])
280 s += "iyy: {0}\n".format(self.matrix['iyy'])
281 s += "iyz: {0}\n".format(self.matrix['iyz'])
282 s += "izz: {0}\n".format(self.matrix['izz'])
283 return s
284
287 UNKNOWN = 'unknown'
288 REVOLUTE = 'revolute'
289 CONTINUOUS = 'continuous'
290 PRISMATIC = 'prismatic'
291 FLOATING = 'floating'
292 PLANAR = 'planar'
293 FIXED = 'fixed'
294
295
296 - def __init__(self, name, parent, child, joint_type, axis=None, origin=None,
297 limits=None, dynamics=None, safety=None, calibration=None,
298 mimic=None):
299 self.name = name
300 self.parent = parent
301 self.child = child
302 self.joint_type = joint_type
303 self.axis = axis
304 self.origin = origin
305 self.limits = limits
306 self.dynamics = dynamics
307 self.safety = safety
308 self.calibration = calibration
309 self.mimic = mimic
310
311 @staticmethod
312 - def parse(node, verbose=True):
313 joint = Joint(node.getAttribute('name'), None, None,
314 node.getAttribute('type'))
315 for child in children(node):
316 if child.localName == 'parent':
317 joint.parent = child.getAttribute('link')
318 elif child.localName == 'child':
319 joint.child = child.getAttribute('link')
320 elif child.localName == 'axis':
321 joint.axis = child.getAttribute('xyz')
322 elif child.localName == 'origin':
323 joint.origin = Pose.parse(child)
324 elif child.localName == 'limit':
325 joint.limits = JointLimit.parse(child)
326 elif child.localName == 'dynamics':
327 joint.dynamics = Dynamics.parse(child)
328 elif child.localName == 'safety_controller':
329 joint.safety = SafetyController.parse(child)
330 elif child.localName == 'calibration':
331 joint.calibration = JointCalibration.parse(child)
332 elif child.localName == 'mimic':
333 joint.mimic = JointMimic.parse(child)
334 else:
335 if verbose:
336 rospy.logwarn("Unknown joint element '%s'"%child.localName)
337 return joint
338
340 xml = doc.createElement("joint")
341 set_attribute(xml, "name", self.name)
342 set_attribute(xml, "type", self.joint_type)
343 xml.appendChild( short(doc, "parent", "link", self.parent) )
344 xml.appendChild( short(doc, "child" , "link", self.child ) )
345 add(doc, xml, self.origin)
346 if self.axis is not None:
347 xml.appendChild( short(doc, "axis", "xyz", self.axis) )
348 add(doc, xml, self.limits)
349 add(doc, xml, self.dynamics)
350 add(doc, xml, self.safety)
351 add(doc, xml, self.calibration)
352 return xml
353
354
356 s = "Name: {0}\n".format(self.name)
357
358 s += "Child link name: {0}\n".format(self.child)
359 s += "Parent link name: {0}\n".format(self.parent)
360
361 if self.joint_type == Joint.UNKNOWN:
362 s += "Type: unknown\n"
363 elif self.joint_type == Joint.REVOLUTE:
364 s += "Type: revolute\n"
365 elif self.joint_type == Joint.CONTINUOUS:
366 s += "Type: continuous\n"
367 elif self.joint_type == Joint.PRISMATIC:
368 s += "Type: prismatic\n"
369 elif self.joint_type == Joint.FLOATING:
370 s += "Type: floating\n"
371 elif self.joint_type == Joint.PLANAR:
372 s += "Type: planar\n"
373 elif self.joint_type == Joint.FIXED:
374 s += "Type: fixed\n"
375 else:
376 rospy.logwarn("unknown joint type")
377
378 s += "Axis: {0}\n".format(self.axis)
379 s += "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
380 s += "Limits:\n"
381 s += reindent(str(self.limits), 1) + "\n"
382 s += "Dynamics:\n"
383 s += reindent(str(self.dynamics), 1) + "\n"
384 s += "Safety:\n"
385 s += reindent(str(self.safety), 1) + "\n"
386 s += "Calibration:\n"
387 s += reindent(str(self.calibration), 1) + "\n"
388 s += "Mimic:\n"
389 s += reindent(str(self.mimic), 1) + "\n"
390 return s
391
395 - def __init__(self, rising=None, falling=None):
396 self.rising = rising
397 self.falling = falling
398
399 @staticmethod
401 jc = JointCalibration()
402 if node.hasAttribute('rising'):
403 jc.rising = float( node.getAttribute('rising') )
404 if node.hasAttribute('falling'):
405 jc.falling = float( node.getAttribute('falling') )
406 return jc
407
409 xml = doc.createElement('calibration')
410 set_attribute(xml, 'rising', self.rising)
411 set_attribute(xml, 'falling', self.falling)
412 return xml
413
415 s = "Raising: {0}\n".format(self.rising)
416 s += "Falling: {0}\n".format(self.falling)
417 return s
418
420 - def __init__(self, effort, velocity, lower=None, upper=None):
421 self.effort = effort
422 self.velocity = velocity
423 self.lower = lower
424 self.upper = upper
425
426 @staticmethod
428 jl = JointLimit( float( node.getAttribute('effort') ) ,
429 float( node.getAttribute('velocity')))
430 if node.hasAttribute('lower'):
431 jl.lower = float( node.getAttribute('lower') )
432 if node.hasAttribute('upper'):
433 jl.upper = float( node.getAttribute('upper') )
434 return jl
435
443
445 s = "Effort: {0}\n".format(self.effort)
446 s += "Lower: {0}\n".format(self.lower)
447 s += "Upper: {0}\n".format(self.upper)
448 s += "Velocity: {0}\n".format(self.velocity)
449 return s
450
453 - def __init__(self, joint_name, multiplier=None, offset=None):
454 self.joint_name = joint_name
455 self.multiplier = multiplier
456 self.offset = offset
457
458 @staticmethod
460 mimic = JointMimic( node.getAttribute('joint') )
461 if node.hasAttribute('multiplier'):
462 mimic.multiplier = float( node.getAttribute('multiplier') )
463 if node.hasAttribute('offset'):
464 mimic.offset = float( node.getAttribute('offset') )
465 return mimic
466
468 xml = doc.createElement('mimic')
469 set_attribute(xml, 'joint', self.joint_name)
470 set_attribute(xml, 'multiplier', self.multiplier)
471 set_attribute(xml, 'offset', self.offset)
472 return xml
473
475 - def __init__(self, name, visual=None, inertial=None, collision=None):
476 self.name = name
477 self.visual = visual
478 self.inertial=inertial
479 self.collision=collision
480
481 @staticmethod
482 - def parse(node, verbose=True):
483 link = Link(node.getAttribute('name'))
484 for child in children(node):
485 if child.localName == 'visual':
486 link.visual = Visual.parse(child, verbose)
487 elif child.localName == 'collision':
488 link.collision = Collision.parse(child, verbose)
489 elif child.localName == 'inertial':
490 link.inertial = Inertial.parse(child)
491 else:
492 if verbose:
493 rospy.logwarn("Unknown link element '%s'"%child.localName)
494 return link
495
497 xml = doc.createElement("link")
498 xml.setAttribute("name", self.name)
499 add( doc, xml, self.visual)
500 add( doc, xml, self.collision)
501 add( doc, xml, self.inertial)
502 return xml
503
505 s = "Name: {0}\n".format(self.name)
506 s += "Inertial:\n"
507 s += reindent(str(self.inertial), 1) + "\n"
508 s += "Collision:\n"
509 s += reindent(str(self.collision), 1) + "\n"
510 return s
511
513 - def __init__(self, name=None, color=None, texture=None):
514 self.name = name
515 self.color = color
516 self.texture = texture
517
518 @staticmethod
519 - def parse(node, verbose=True):
520 material = Material()
521 if node.hasAttribute('name'):
522 material.name = node.getAttribute('name')
523 for child in children(node):
524 if child.localName == 'color':
525 material.color = Color.parse(child)
526 elif child.localName == 'texture':
527 material.texture = child.getAttribute('filename')
528 else:
529 if verbose:
530 rospy.logwarn("Unknown material element '%s'"%child.localName)
531
532 return material
533
535 xml = doc.createElement("material")
536 set_attribute(xml, "name", self.name)
537 add( doc, xml, self.color )
538
539 if self.texture is not None:
540 text = doc.createElement("texture")
541 text.setAttribute('filename', self.texture)
542 xml.appendChild(text)
543 return xml
544
546 s = "Name: {0}\n".format(self.name)
547 s += "Color: {0}\n".format(self.color)
548 s += "Texture:\n"
549 s += reindent(str(self.texture), 1)
550 return s
551
552
553 -class Pose(object):
554 - def __init__(self, position=None, rotation=None):
555 self.position = position
556 self.rotation = rotation
557
558 @staticmethod
560 pose = Pose()
561 if node.hasAttribute("xyz"):
562 xyz = node.getAttribute('xyz').split()
563 pose.position = map(float, xyz)
564 if node.hasAttribute("rpy"):
565 rpy = node.getAttribute('rpy').split()
566 pose.rotation = map(float, rpy)
567 return pose
568
570 xml = doc.createElement("origin")
571 set_attribute(xml, 'xyz', self.position)
572 set_attribute(xml, 'rpy', self.rotation)
573 return xml
574
575
577 return "Position: {0}\nRotation: {1}".format(self.position,
578 self.rotation)
579
582 - def __init__(self, velocity, position=None, lower=None, upper=None):
583 self.velocity = velocity
584 self.position = position
585 self.lower = lower
586 self.upper = upper
587
588 @staticmethod
590 sc = SafetyController( float(node.getAttribute('k_velocity')) )
591 if node.hasAttribute('soft_lower_limit'):
592 sc.lower = float( node.getAttribute('soft_lower_limit') )
593 if node.hasAttribute('soft_upper_limit'):
594 sc.upper = float( node.getAttribute('soft_upper_limit') )
595 if node.hasAttribute('k_position'):
596 sc.position = float( node.getAttribute('k_position') )
597 return sc
598
600 xml = doc.createElement('safety_controller')
601 set_attribute(xml, 'k_velocity', self.velocity)
602 set_attribute(xml, 'k_position', self.position)
603 set_attribute(xml, 'soft_upper_limit', self.upper)
604 set_attribute(xml, 'soft_lower_limit', self.lower)
605 return xml
606
608 s = "Safe lower limit: {0}\n".format(self.lower)
609 s += "Safe upper limit: {0}\n".format(self.upper)
610 s += "K position: {0}\n".format(self.position)
611 s += "K velocity: {0}\n".format(self.velocity)
612 return s
613
616 - def __init__(self, geometry=None, material=None, origin=None):
617 self.geometry = geometry
618 self.material = material
619 self.origin = origin
620
621 @staticmethod
622 - def parse(node, verbose=True):
623 v = Visual()
624 for child in children(node):
625 if child.localName == 'geometry':
626 v.geometry = Geometry.parse(child, verbose)
627 elif child.localName == 'origin':
628 v.origin = Pose.parse(child)
629 elif child.localName == 'material':
630 v.material = Material.parse(child, verbose)
631 else:
632 if verbose:
633 rospy.logwarn("Unknown visual element '%s'"%child.localName)
634 return v
635
637 xml = doc.createElement("visual")
638 add( doc, xml, self.geometry )
639 add( doc, xml, self.origin )
640 add( doc, xml, self.material )
641 return xml
642
644 s = "Origin:\n{0}\n".format(reindent(str(self.origin), 1))
645 s += "Geometry:\n"
646 s += reindent(str(self.geometry), 1) + "\n"
647 s += "Material:\n"
648 s += reindent(str(self.material), 1) + "\n"
649 return s
650
653 self.name = name
654 self.elements = []
655 self.links = {}
656 self.joints = {}
657 self.materials = {}
658
659 self.parent_map = {}
660 self.child_map = {}
661
662 @staticmethod
664 """Parse a string to create a URDF robot structure."""
665 urdf = URDF()
666 base = xml.dom.minidom.parseString(xml_string)
667 robot = children(base)[0]
668 urdf.name = robot.getAttribute('name')
669
670 for node in children(robot):
671 if node.nodeType is node.TEXT_NODE:
672 continue
673 if node.localName == 'joint':
674 urdf.add_joint( Joint.parse(node, verbose) )
675 elif node.localName == 'link':
676 urdf.add_link( Link.parse(node, verbose) )
677 elif node.localName == 'material':
678 urdf.elements.append( Material.parse(node, verbose) )
679 elif node.localName == 'gazebo':
680 None
681 elif node.localName == 'transmission':
682 None
683 else:
684 if verbose:
685 rospy.logwarn("Unknown robot element '%s'"%node.localName)
686 return urdf
687
688 @staticmethod
690 """Parse a file to create a URDF robot structure."""
691 f = open(filename, 'r')
692 return URDF.parse_xml_string(f.read(), verbose)
693
694 @staticmethod
696 """
697 Retrieve the robot model on the parameter server
698 and parse it to create a URDF robot structure.
699
700 Warning: this requires roscore to be running.
701 """
702 import rospy
703 return URDF.parse_xml_string(rospy.get_param(key), verbose)
704
706 self.elements.append(link)
707 self.links[link.name] = link
708
710 self.elements.append(joint)
711 self.joints[joint.name] = joint
712
713 self.parent_map[ joint.child ] = (joint.name, joint.parent)
714 if joint.parent in self.child_map:
715 self.child_map[joint.parent].append( (joint.name, joint.child) )
716 else:
717 self.child_map[joint.parent] = [ (joint.name, joint.child) ]
718
719
720 - def get_chain(self, root, tip, joints=True, links=True, fixed=True):
721 chain = []
722 if links:
723 chain.append(tip)
724 link = tip
725 while link != root:
726 (joint, parent) = self.parent_map[link]
727 if joints:
728 if fixed or self.joints[joint].joint_type != 'fixed':
729 chain.append(joint)
730 if links:
731 chain.append(parent)
732 link = parent
733 chain.reverse()
734 return chain
735
737 root = None
738 for link in self.links:
739 if link not in self.parent_map:
740 assert root is None, "Multiple roots detected, invalid URDF."
741 root = link
742 assert root is not None, "No roots detected, invalid URDF."
743 return root
744
746 doc = Document()
747 root = doc.createElement("robot")
748 doc.appendChild(root)
749 root.setAttribute("name", self.name)
750
751 for element in self.elements:
752 root.appendChild(element.to_xml(doc))
753
754 return doc.toprettyxml()
755
756
758 s = "Name: {0}\n".format(self.name)
759 s += "\n"
760 s += "Links:\n"
761 if len(self.links) == 0:
762 s += "None\n"
763 else:
764 for k, v in self.links.iteritems():
765 s += "- Link '{0}':\n{1}\n".format(k, reindent(str(v), 1))
766 s += "\n"
767 s += "Joints:\n"
768 if len(self.joints) == 0:
769 s += "None\n"
770 else:
771 for k, v in self.joints.iteritems():
772 s += "- Joint '{0}':\n{1}\n".format(k, reindent(str(v), 1))
773 s += "\n"
774 s += "Materials:\n"
775 if len(self.materials) == 0:
776 s += "None\n"
777 else:
778 for k, v in self.materials.iteritems():
779 s += "- Material '{0}':\n{1}\n".format(k, reindent(str(v), 1))
780
781 return s
782
783 self.name = name
784 self.elements = []
785 self.links = {}
786 self.joints = {}
787 self.materials = {}
788
789 self.parent_map = {}
790 self.child_map = {}
791