more fixes in pybullet/resources, moved enjoy/train/test in 'examples' folder.
This commit is contained in:
@@ -8,8 +8,19 @@
|
|||||||
<!-- geometry macros -->
|
<!-- geometry macros -->
|
||||||
<!-- transmission macros -->
|
<!-- transmission macros -->
|
||||||
<!-- Add chassis and it's inertia link -->
|
<!-- Add chassis and it's inertia link -->
|
||||||
<link name="base_link"/>
|
<link name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
<link name="chassis">
|
<link name="chassis">
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
||||||
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -478,8 +489,5 @@
|
|||||||
<material name="red">
|
<material name="red">
|
||||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
<material name="white">
|
|
||||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
|
||||||
</material>
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
||||||
|
|||||||
@@ -1,23 +0,0 @@
|
|||||||
|
|
||||||
from pybullet_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)
|
|
||||||
@@ -8,8 +8,19 @@
|
|||||||
<!-- geometry macros -->
|
<!-- geometry macros -->
|
||||||
<!-- transmission macros -->
|
<!-- transmission macros -->
|
||||||
<!-- Add chassis and it's inertia link -->
|
<!-- Add chassis and it's inertia link -->
|
||||||
<link name="base_link"/>
|
<link name="base_link">
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
<link name="chassis">
|
<link name="chassis">
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
||||||
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
@@ -478,8 +489,5 @@
|
|||||||
<material name="red">
|
<material name="red">
|
||||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||||
</material>
|
</material>
|
||||||
<material name="white">
|
|
||||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
|
||||||
</material>
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|
||||||
|
|||||||
@@ -1,3 +1,10 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os
|
||||||
|
import inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,10 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os
|
||||||
|
import inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
@@ -1,7 +1,13 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
import envs
|
import pybullet_envs
|
||||||
import time
|
import time
|
||||||
|
|
||||||
def relu(x):
|
def relu(x):
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
|
|
||||||
from baselines import deepq
|
from baselines import deepq
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,8 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||||
import time
|
import time
|
||||||
@@ -1,3 +1,8 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||||
print ("hello")
|
print ("hello")
|
||||||
@@ -1,3 +1,8 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||||
print ("hello")
|
print ("hello")
|
||||||
@@ -1,3 +1,8 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
from pybullet_envs.bullet.simpleHumanoidGymEnv import SimpleHumanoidGymEnv
|
from pybullet_envs.bullet.simpleHumanoidGymEnv import SimpleHumanoidGymEnv
|
||||||
print ("hello")
|
print ("hello")
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.kukaCamGymEnv import KukaCamGymEnv
|
from pybullet_envs.bullet.kukaCamGymEnv import KukaCamGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
|
||||||
|
|
||||||
@@ -1,3 +1,9 @@
|
|||||||
|
#add parent dir to find package. Only needed for source code build, pip install doesn't need it.
|
||||||
|
import os, inspect
|
||||||
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
|
os.sys.path.insert(0,parentdir)
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
|
||||||
|
|
||||||
Reference in New Issue
Block a user