add nicer meshes to kuka_with_gripper.sdf and add kuka_with_gripper2.sdf that can rotate without messing up IK
fix tray/tray_textured4.obj and tray/tray.urdf fix kuka_with_cube.py allow both IK /end-effector control and joint-space control in kuka environment, use 1./240. sec. step and 150 solver iter bump up pybullet to 1.1.7
This commit is contained in:
@@ -20,7 +20,7 @@ class KukaGymEnv(gym.Env):
|
||||
isEnableSelfCollision=True,
|
||||
renders=True):
|
||||
print("init")
|
||||
self._timeStep = 0.01
|
||||
self._timeStep = 1./240.
|
||||
self._urdfRoot = urdfRoot
|
||||
self._actionRepeat = actionRepeat
|
||||
self._isEnableSelfCollision = isEnableSelfCollision
|
||||
@@ -45,7 +45,7 @@ class KukaGymEnv(gym.Env):
|
||||
|
||||
def _reset(self):
|
||||
p.resetSimulation()
|
||||
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=150)
|
||||
p.setTimeStep(self._timeStep)
|
||||
p.loadURDF("%splane.urdf" % self._urdfRoot,[0,0,-1])
|
||||
|
||||
|
||||
Reference in New Issue
Block a user