6 from xml.dom.minidom
import Document
7 from xml.dom
import minidom
9 from numpy
import array, pi
13 HUBO_JOINT_SUFFIX_MASK =
r'([HKASEWF][RPY12345])' 17 """Collision node stores collision geometry for a link.""" 18 def __init__(self, geometry=None, origin=None):
26 if child.localName ==
'geometry':
27 c.geometry = Geometry.parse(child, verbose)
28 elif child.localName ==
'origin':
29 c.origin = Pose.parse(child)
31 print(
"Unknown collision element '%s'" % child.localName)
35 xml = doc.createElement(
"collision")
42 xml = self.geometry.to_openrave_xml(doc)
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):
59 rgba = node.getAttribute(
"rgba").split()
60 (r, g, b, a) = [float(x)
for x
in rgba]
61 return Color(r, g, b, a)
64 xml = doc.createElement(
"color")
72 return "r: {0}, g: {1}, b: {2}, a: {3}, ".format(
77 """Dynamics node stores coefficients that define the dynamics of a joint""" 78 def __init__(self, damping=None, friction=None):
85 if node.hasAttribute(
'damping'):
86 d.damping = node.getAttribute(
'damping')
87 if node.hasAttribute(
'friction'):
88 d.friction = node.getAttribute(
'friction')
92 xml = doc.createElement(
'dynamics')
101 return "Damping: {0}\nFriction: {1}\n".format(self.
damping,
106 """Geometry abstract class define the type of geomerical shape for a visual or collision element""" 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)
123 print(
"Unknown shape %s" % shape.localName)
126 return "Geometry abstract class" 130 """Box node stores the dimensions for a rectangular geometry element""" 135 self.
dims = (dims[0], dims[1], dims[2])
139 dims = node.getAttribute(
'size').split()
140 return Box([float(a)
for a
in dims])
143 xml = doc.createElement(
"box")
145 geom = doc.createElement(
'geometry')
146 geom.appendChild(xml)
150 xml =
short(doc,
"geometry",
"type",
"box")
155 return "Dimension: {0}".format(self.
dims)
159 """Cylinder node stores the dimensions for a z-rotation invariant geometry element""" 166 r = node.getAttribute(
'radius')
167 l = node.getAttribute(
'length')
171 xml = doc.createElement(
"cylinder")
174 geom = doc.createElement(
'geometry')
175 geom.appendChild(xml)
179 xml =
short(doc,
"geometry",
"type",
"cylinder")
185 return "Radius: {0}\nLength: {1}".format(self.
radius,
190 """Sphere node stores the dimensions for a rotation invariant geometry element""" 196 r = node.getAttribute(
'radius')
200 xml = doc.createElement(
"sphere")
202 geom = doc.createElement(
'geometry')
203 geom.appendChild(xml)
207 xml =
short(doc,
"geometry",
"type",
"sphere")
208 xml.create_child(xml,
"radius", self.
radius)
212 return "Radius: {0}".format(self.
radius)
216 """Mesh node stores the path of the mesh file to be displayed""" 223 fn = node.getAttribute(
'filename')
224 s = node.getAttribute(
'scale')
228 xyz = node.getAttribute(
'scale').split()
233 xml = doc.createElement(
"mesh")
237 geom = doc.createElement(
'geometry')
238 geom.appendChild(xml)
242 xml =
short(doc,
"geometry",
"type",
"trimesh")
243 f =
'../meshes/' + self.filename.split(
'/')[-1]
244 fhull = re.sub(
r"Body",
"convhull", f)
251 return "Filename: {0}\nScale: {1}".format(self.
filename, self.
scale)
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):
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)
282 xml = doc.createElement(
"inertial")
284 xml.appendChild(
short(doc,
"mass",
"value", self.
mass))
286 inertia = doc.createElement(
"inertia")
287 for (n, v)
in self.matrix.items():
289 xml.appendChild(inertia)
295 xml = doc.createElement(
"mass")
298 text =
'{ixx} {ixy} {ixz}\n{ixy} {iyy} {iyz}\n{ixz} {iyz} {izz}'.format(**self.
matrix)
301 xml.getElementsByTagName(
'translation')[0].tagName =
"com" 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'])
317 """Joint node stores articulation information coupling two links""" 319 REVOLUTE =
'revolute' 320 CONTINUOUS =
'continuous' 321 PRISMATIC =
'prismatic' 322 FLOATING =
'floating' 326 def __init__(self, name, parent, child, joint_type, axis=None, origin=None,
327 limits=
None, dynamics=
None, safety=
None, calibration=
None,
343 joint =
Joint(node.getAttribute(
'name'),
None,
None,
344 node.getAttribute(
'type'))
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)
366 print(
"Unknown joint element '%s'" % child.localName)
370 xml = doc.createElement(
"joint")
373 xml.appendChild(
short(doc,
"parent",
"link", self.
parent))
374 xml.appendChild(
short(doc,
"child",
"link", self.
child))
376 if self.
axis is not None:
387 xml = doc.createElement(
"joint")
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
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))
418 xml.getElementsByTagName(
'translation')[0].tagName =
"anchor" 419 if self.
axis is not None:
425 s =
"Name: {0}\n".format(self.
name)
427 s +=
"Child link name: {0}\n".format(self.
child)
428 s +=
"Parent link name: {0}\n".format(self.
parent)
431 s +=
"Type: unknown\n" 433 s +=
"Type: revolute\n" 435 s +=
"Type: continuous\n" 437 s +=
"Type: prismatic\n" 439 s +=
"Type: floating\n" 441 s +=
"Type: planar\n" 445 print(
"unknown joint type")
447 s +=
"Axis: {0}\n".format(self.
axis)
455 s +=
"Calibration:\n" 471 if node.hasAttribute(
'rising'):
472 jc.rising = float(node.getAttribute(
'rising'))
473 if node.hasAttribute(
'falling'):
474 jc.falling = float(node.getAttribute(
'falling'))
478 xml = doc.createElement(
'calibration')
488 s =
"Raising: {0}\n".format(self.
rising)
489 s +=
"Falling: {0}\n".format(self.
falling)
494 """JointLimit node stores mechanical limits of a given joint""" 495 def __init__(self, effort, velocity, lower=None, upper=None):
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'))
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'))
521 xml = doc.createElement(
'limit')
532 return [limit, maxvel, maxtrq]
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)
543 """JointMimic node stores information coupling an actuated joint to a not controllable joint""" 544 def __init__(self, joint_name, multiplier=None, offset=None):
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'))
559 xml = doc.createElement(
'mimic')
567 s +=
"Multiplier: {0}\n".format(self.
multiplier)
568 s +=
"Offset: {0}\n".format(self.
offset)
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):
583 link =
Link(node.getAttribute(
'name'))
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'):
595 print(
"Unknown link element '%s'" % child.localName)
599 xml = doc.createElement(
"link")
600 xml.setAttribute(
"name", self.
name)
604 if self.
xacro is not None:
605 text = doc.createElement(self.
xacro)
606 xml.appendChild(text)
610 xml = doc.createElement(
"body")
611 xml.setAttribute(
"name", self.
name)
617 s =
"Name: {0}\n".format(self.
name)
630 """Material node stores visual information of a mechanical material : color, texture""" 631 def __init__(self, name=None, color=None, texture=None):
639 if node.hasAttribute(
'name'):
640 material.name = node.getAttribute(
'name')
642 if child.localName ==
'color':
643 material.color = Color.parse(child)
644 elif child.localName ==
'texture':
645 material.texture = child.getAttribute(
'filename')
648 print(
"Unknown material element '%s'" % child.localName)
653 xml = doc.createElement(
"material")
658 text = doc.createElement(
"texture")
659 text.setAttribute(
'filename', self.
texture)
660 xml.appendChild(text)
664 s =
"Name: {0}\n".format(self.
name)
665 s +=
"Color: {0}\n".format(self.
color)
672 """Pose node stores a cartesian 6-D 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))
692 xml = doc.createElement(
"origin")
698 xml = doc.createElement(
"translation")
702 rotr = doc.createElement(
"rotationaxis")
704 elements.append(rotr)
706 rotp = doc.createElement(
"rotationaxis")
708 elements.append(rotp)
710 roty = doc.createElement(
"rotationaxis")
712 elements.append(roty)
717 return "Position: {0}\nRotation: {1}".format(self.
position,
722 def __init__(self, velocity, position=None, lower=None, upper=None):
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'))
740 xml = doc.createElement(
'safety_controller')
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)
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):
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)
774 print(
"Unknown visual element '%s'" % child.localName)
778 xml = doc.createElement(
"visual")
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):
803 if node.hasAttribute(
'name'):
804 actuator.name = node.getAttribute(
'name')
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)
811 print'Unknown actuator element ' + str(child.localName)
815 xml = doc.createElement(
'actuator')
822 s =
"Name: {0}\n".format(self.
name)
829 """Transmission node stores information linking a joint to an actuator""" 830 def __init__(self, name=None, type=None, joint=None, actuator=None):
839 if node.hasAttribute(
'name'):
840 trans.name = node.getAttribute(
'name')
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)
852 xml = doc.createElement(
'transmission')
854 xml.appendChild(
short(doc,
"joint",
"name", self.
joint))
861 s =
"Name: {0}\n".format(self.
name)
862 s +=
"Type: {0}\n".format(self.
type)
863 s +=
"Joint: {0}\n".format(self.
joint)
874 """URDF node stores every information about a robot's model""" 875 ZERO_THRESHOLD = 0.000000001
889 """Parse a string to create a URDF robot structure.""" 891 base = minidom.parseString(xml_string)
893 urdf.name = robot.getAttribute(
'name')
896 if node.nodeType
is node.TEXT_NODE:
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))
910 print(
"Unknown robot element '%s'" % node.localName)
915 """Parse a file to create a URDF robot structure.""" 916 f = open(filename,
'r') 917 return URDF.parse_xml_string(f.read(), verbose)
922 Retrieve the robot model on the parameter server 923 and parse it to create a URDF robot structure. 925 Warning: this requires roscore to be running. 928 return URDF.parse_xml_string(rospy.get_param(key), verbose)
931 self.elements.append(link)
932 self.
links[link.name] = link
935 self.elements.append(joint)
936 self.
joints[joint.name] = joint
938 self.
parent_map[joint.child] = (joint.name, joint.parent)
940 self.
child_map[joint.parent].append((joint.name, joint.child))
942 self.
child_map[joint.parent] = [(joint.name, joint.child)]
946 Add a material to the URDF.elements list 948 self.elements.append(material)
953 Add gazebo data to the URDF.elements list 956 self.elements.append(gazebo)
957 self.
gazebos[gazebo.reference] = gazebo
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.""" 968 if fixed
or self.
joints[joint].joint_type !=
'fixed':
978 for link
in self.
links:
980 assert root
is None,
"Multiple roots detected, invalid URDF." 982 assert root
is not None,
"No roots detected, invalid URDF." 985 def to_xml(self, orderbytree=False, orderbytype=False):
987 root = doc.createElement(
"robot")
988 doc.appendChild(root)
989 root.setAttribute(
"name", self.
name)
999 root.appendChild(element.to_xml(doc))
1001 return doc.toprettyxml()
1005 outfile = self.
name +
'.urdf' 1010 kinbody = doc.createElement(
"kinbody")
1011 doc.appendChild(kinbody)
1012 kinbody.setAttribute(
"name", self.
name)
1015 kinbody.appendChild(element.to_openrave_xml(doc))
1019 for j
in self.joints.keys():
1020 for l
in kinbody.getElementsByTagName(
'body'):
1021 if l.getAttribute(
'name') == self.
joints[j].child:
1028 for j
in self.joints.values():
1029 kinbody.appendChild(
create_element(doc,
"adjacent", [j.parent, j.child]))
1032 badjoints = {
'LAR':
'LKP',
'LWR':
'LWY',
'LSY':
'LSP',
'LHY':
'LHP',
1033 'RAR':
'RKP',
'RWR':
'RWY',
'RSY':
'RSP',
'RHY':
'RHP',
1035 for k, v
in badjoints.items():
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')
1051 root = doc.createElement(
"robot")
1052 doc.appendChild(root)
1053 root.setAttribute(
"name", self.
name)
1056 return doc.toprettyxml()
1061 outdata = re.sub(
r'\t',
' ', data)
1062 with open(name,
'w+')
as f:
1069 kinfile = outname +
'.kinbody.xml' 1072 robotfile = outname +
'.robot.xml' 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)
1089 s =
"Name: {0}\n".format(self.
name)
1092 if len(self.
links) == 0:
1095 for k, v
in self.links.iteritems():
1096 s +=
"- Link '{0}':\n{1}\n".format(k,
reindent(str(v), 1))
1099 if len(self.
joints) == 0:
1102 for k, v
in self.joints.iteritems():
1103 s +=
"- Joint '{0}':\n{1}\n".format(k,
reindent(str(v), 1))
1109 for k, v
in self.materials.iteritems():
1110 s +=
"- Material '{0}':\n{1}\n".format(k,
reindent(str(v), 1))
1115 """Walk along the first branch of urdf tree to find last link. Optionally specify which fork to take globally).""" 1117 if branchorder
is None:
1123 child = children[
min(branchorder, l - 1)][1]
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
1132 self.links.pop(link)
1133 for k, v
in self.parent_map.items():
1136 self.parent_map.pop(k)
1145 for k, v
in self.child_map.items():
1148 self.child_map.pop(k)
1153 el = (el[0], newlink)
1157 for n, j
in self.joints.items():
1158 if j.parent == link:
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
1170 self.joints.pop(joint)
1171 for k, v
in self.child_map.items():
1175 el = (newjoint, el[1])
1179 for k, v
in self.parent_map.items():
1181 v = (newjoint, v[1])
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
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)
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 1204 linkchain = self.
get_chain(root, tip, links=
True, joints=
False)
1205 jointchain = self.
get_chain(root, tip, joints=
True, links=
False)
1209 for l
in linkchain[1:]:
1210 newlink = re.sub(f, r, l)
1212 for j
in jointchain:
1213 newname = re.sub(f, r, j)
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)
1221 """Copy a kinematic chain, renaming joints and links according to a regular expression. 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. 1229 linkchain = self.
get_chain(root, tip, links=
True, joints=
False)
1230 jointchain = self.
get_chain(root, tip, joints=
True, links=
False)
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)
1242 newlinks.append(newlink)
1244 newlink.inertial.matrix[
'ixy'] *= -1.
1245 newlink.inertial.matrix[
'ixz'] *= -1.
1246 newlink.inertial.origin.position[0] *= -1.
1248 newlink.inertial.matrix[
'ixy'] *= -1.
1249 newlink.inertial.matrix[
'iyz'] *= -1.
1250 newlink.inertial.origin.position[1] *= -1.
1252 newlink.inertial.matrix[
'ixz'] *= -1.
1253 newlink.inertial.matrix[
'iyz'] *= -1.
1254 newlink.inertial.origin.position[2] *= -1.
1256 for j
in jointchain:
1259 newjoints[-1].origin.position[0] *= -1.0
1260 newjoints[-1].origin.rotation[1] *= -1.0
1261 newjoints[-1].origin.rotation[2] *= -1.0
1263 newjoints[-1].origin.position[1] *= -1.0
1264 newjoints[-1].origin.rotation[0] *= -1.0
1265 newjoints[-1].origin.rotation[2] *= -1.0
1267 newjoints[-1].origin.position[2] *= -1.0
1268 newjoints[-1].origin.rotation[0] *= -1.0
1269 newjoints[-1].origin.rotation[1] *= -1.0
1271 if mir_ax ==
'rotx':
1272 newjoints[0].origin.position[1] *= -1.0
1275 if j.mimic
is not None:
1276 j.mimic.joint_name = re.sub(f, r, j.mimic.joint_name)
1278 newjoints[0].origin.position += array(xyz)
1279 newjoints[0].origin.rotation += array(rpy)
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)
1288 """Search and replace package paths in urdf with chosen package name""" 1289 for n, l
in self.links.items():
1291 for g
in [l.collision.geometry, l.visual.geometry]:
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)
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
1307 if __name__ ==
'__main__':
1314 filename = sys.argv[1]
1316 print(
'Please supply a URDF filename to convert!')
1319 outname = sys.argv[2]
1323 model = URDF.load_xml_file(filename)
1325 model.write_openrave_files(outname)