more fixes in the pybullet gym environments: use main instead of demo_run,
add missing main to some eaxmples.
pip install pybullet
train:
python -m pybullet_envs.examples.train_pybullet_cartpole
enjoy:
python -m pybullet_envs.examples.enjoy_pybullet_cartpole
enjoy pretrained environments:
python -m pybullet_envs.examples.enjoy_TF_AntBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_HalfCheetahBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_AntBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_HopperBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_HumanoidBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_InvertedPendulumBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may
python -m pybullet_envs.examples.enjoy_TF_Walker2DBulletEnv_v0_2017may
Run some gym environment test:
python -m pybullet_envs.examples.racecarGymEnvTest
Create/Import a specific Gym environment:
python
import pybullet_envs
env = gym.make("AntBulletEnv-v0")
env = gym.make("HalfCheetahBulletEnv-v0")
env = gym.make("HopperBulletEnv-v0")
env = gym.make("HumanoidBulletEnv-v0")
env = gym.make("Walker2DBulletEnv-v0")
env = gym.make("InvertedDoublePendulumBulletEnv-v0")
env = gym.make("InvertedPendulumBulletEnv-v0")
env = gym.make("MinitaurBulletEnv-v0")
env = gym.make("RacecarBulletEnv-v0")
env = gym.make("KukaBulletEnv-v0")
env = gym.make("CartPoleBulletEnv-v0")
This commit is contained in:
@@ -7,31 +7,34 @@ os.sys.path.insert(0,parentdir)
|
||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||
import time
|
||||
|
||||
def main():
|
||||
|
||||
environment = KukaGymEnv(renders=True)
|
||||
|
||||
|
||||
motorsIds=[]
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
|
||||
|
||||
dv = 0.001
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posX",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posY",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posZ",-dv,dv,-dv))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("yaw",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
|
||||
|
||||
done = False
|
||||
while (not done):
|
||||
|
||||
action=[]
|
||||
for motorId in motorsIds:
|
||||
action.append(environment._p.readUserDebugParameter(motorId))
|
||||
|
||||
state, reward, done, info = environment.step2(action)
|
||||
obs = environment.getExtendedObservation()
|
||||
|
||||
environment = KukaGymEnv(renders=True)
|
||||
|
||||
|
||||
motorsIds=[]
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
|
||||
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
|
||||
|
||||
dv = 0.001
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posX",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posY",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("posZ",-dv,dv,-dv))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("yaw",-dv,dv,0))
|
||||
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
|
||||
|
||||
done = False
|
||||
while (not done):
|
||||
|
||||
action=[]
|
||||
for motorId in motorsIds:
|
||||
action.append(environment._p.readUserDebugParameter(motorId))
|
||||
|
||||
state, reward, done, info = environment.step2(action)
|
||||
obs = environment.getExtendedObservation()
|
||||
|
||||
if __name__=="__main__":
|
||||
main()
|
||||
Reference in New Issue
Block a user