PyBullet urdfEditor improvements: saveUrdf mesh scale, fix incorrect index, add getCameraImage in examples/combineUrdf.py

This commit is contained in:
Erwin Coumans
2018-05-09 10:28:12 -07:00
parent 1e51e2b859
commit 414b3ef9bb
4 changed files with 14 additions and 7 deletions

View File

@@ -85,17 +85,21 @@ joint.joint_axis_xyz = [0,0,1]
#so make sure to insert the joint in the right place, to links/joints match
ed0.urdfJoints.insert(insertJointIndex,joint)
ed0.saveUrdf("combined.urdf")
print(p0._client)
print(p1._client)
print("p0.getNumBodies()=",p0.getNumBodies())
print("p1.getNumBodies()=",p1.getNumBodies())
pgui = bc.BulletClient(connection_mode=pybullet.GUI)
ed0.createMultiBody([0,0,0],pgui._client)
pgui.setRealTimeSimulation(1)
ed0.saveUrdf("combined.urdf")
while (pgui.isConnected()):
time.sleep(1./240.)
pgui.getCameraImage(320,200)
time.sleep(1./240.)

View File

@@ -8,5 +8,6 @@ p.loadURDF("combined.urdf", useFixedBase=True)
# p.setJointMotorControl2(0,j,p.VELOCITY_CONTROL,targetVelocity=0.1)
p.setRealTimeSimulation(1)
while (p.isConnected()):
p.getCameraImage(320,200)
import time
time.sleep(1./240.)

View File

@@ -216,7 +216,9 @@ class UrdfEditor(object):
prec=precision)
file.write(str)
if urdfVisual.geom_type == p.GEOM_MESH:
str = '\t\t\t\t<mesh filename=\"{}\"/>\n'.format(urdfVisual.geom_meshfilename,\
str = '\t\t\t\t<mesh filename=\"{}\" scale=\"{:.{prec}f} {:.{prec}f} {:.{prec}f}\"/>\n'.format(
urdfVisual.geom_meshfilename,urdfVisual.geom_meshscale[0],urdfVisual.geom_meshscale[1],urdfVisual.geom_meshscale[2],\
prec=precision)
file.write(str)
if urdfVisual.geom_type == p.GEOM_CYLINDER:
@@ -253,8 +255,8 @@ class UrdfEditor(object):
prec=precision)
file.write(str)
if urdfCollision.geom_type == p.GEOM_MESH:
str = '\t\t\t\t<mesh filename=\"{}\"/>\n'.format(urdfCollision.geom_meshfilename,\
prec=precision)
str = '\t\t\t\t<mesh filename=\"{}\"/> scale=\"{:.{prec}f} {:.{prec}f} {:.{prec}f}\"\n'.format(urdfCollision.geom_meshfilename,\
urdfCollision.geom_meshscale[0],urdfCollision.geom_meshscale[1],urdfCollision.geom_meshscale[2],prec=precision)
file.write(str)
if urdfCollision.geom_type == p.GEOM_CYLINDER:
str = '\t\t\t\t<cylinder length=\"{:.{prec}f}\" radius=\"{:.{prec}f}\"/>\n'.format(\