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:
23
examples/pybullet/gym/kukaJointSpaceGymEnvTest.py
Normal file
23
examples/pybullet/gym/kukaJointSpaceGymEnvTest.py
Normal file
@@ -0,0 +1,23 @@
|
||||
|
||||
from envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
import time
|
||||
|
||||
|
||||
environment = KukaGymEnv(renders=True)
|
||||
environment._kuka.useInverseKinematics=0
|
||||
|
||||
motorsIds=[]
|
||||
for i in range (len(environment._kuka.motorNames)):
|
||||
motor = environment._kuka.motorNames[i]
|
||||
motorJointIndex = environment._kuka.motorIndices[i]
|
||||
motorsIds.append(environment._p.addUserDebugParameter(motor,-3,3,environment._kuka.jointPositions[i]))
|
||||
|
||||
while (True):
|
||||
|
||||
action=[]
|
||||
for motorId in motorsIds:
|
||||
action.append(environment._p.readUserDebugParameter(motorId))
|
||||
|
||||
state, reward, done, info = environment.step(action)
|
||||
obs = environment.getExtendedObservation()
|
||||
time.sleep(0.01)
|
||||
Reference in New Issue
Block a user