add rudimentary MuJoCo mjcf xml to ROS URDF file, based on

pybullet_utils.urdfEditor
This commit is contained in:
Erwin Coumans
2018-10-31 11:02:19 -07:00
parent 624212c641
commit 8e82de1b00
4 changed files with 74 additions and 26 deletions

View File

@@ -1,7 +1,6 @@
import pybullet as p
import time
class UrdfInertial(object):
def __init__(self):
self.mass = 1
@@ -201,6 +200,10 @@ class UrdfEditor(object):
file.write("\t\t</inertial>\n")
def writeVisualShape(self,file,urdfVisual, precision=5):
#we don't support loading capsule types from visuals, so auto-convert from collision shape
if urdfVisual.geom_type == p.GEOM_CAPSULE:
return
file.write("\t\t<visual>\n")
str = '\t\t\t<origin rpy="{:.{prec}f} {:.{prec}f} {:.{prec}f}" xyz="{:.{prec}f} {:.{prec}f} {:.{prec}f}"/>\n'.format(\
urdfVisual.origin_rpy[0],urdfVisual.origin_rpy[1],urdfVisual.origin_rpy[2],
@@ -276,8 +279,13 @@ class UrdfEditor(object):
file.write("\">\n")
self.writeInertial(file,urdfLink.urdf_inertial)
hasCapsules = False
for v in urdfLink.urdf_visual_shapes:
self.writeVisualShape(file,v)
if (v.geom_type == p.GEOM_CAPSULE):
hasCapsules = True
if (not hasCapsules):
for v in urdfLink.urdf_visual_shapes:
self.writeVisualShape(file,v)
for c in urdfLink.urdf_collision_shapes:
self.writeCollisionShape(file,c)
file.write("\t</link>\n")