Add nearly all gym environments using pybullet together with the latest tf model from the roboschool model zoo.
This commit is contained in:
233
examples/pybullet/gym/envs/gym_forward_walkers.py
Normal file
233
examples/pybullet/gym/envs/gym_forward_walkers.py
Normal file
@@ -0,0 +1,233 @@
|
||||
from distutils.command.config import config
|
||||
|
||||
from pybulletgym.envs.scene_abstract import SingleRobotEmptyScene
|
||||
from pybulletgym.envs.scene_stadium import SinglePlayerStadiumScene
|
||||
from gym_mujoco_xml_env import PybulletMujocoXmlEnv
|
||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||
import numpy as np
|
||||
import os, sys
|
||||
|
||||
class PybulletForwardWalkersBase(PybulletMujocoXmlEnv):
|
||||
def __init__(self, fn, robot_name, action_dim, obs_dim, power):
|
||||
PybulletMujocoXmlEnv.__init__(self, fn, robot_name, action_dim, obs_dim)
|
||||
self.power = power
|
||||
self.camera_x = 0
|
||||
self.walk_target_x = 1e3 # kilometer away
|
||||
self.walk_target_y = 0
|
||||
|
||||
def create_single_player_scene(self):
|
||||
self.stadium_scene = SinglePlayerStadiumScene(gravity=9.8, timestep=0.0165/4, frame_skip=4)
|
||||
return self.stadium_scene
|
||||
|
||||
def robot_specific_reset(self):
|
||||
for j in self.ordered_joints:
|
||||
j.reset_current_position(self.np_random.uniform( low=-0.1, high=0.1 ), 0)
|
||||
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self.stadium_scene.ground_plane_mjcf)
|
||||
self.feet = [self.parts[f] for f in self.foot_list]
|
||||
self.feet_contact = np.array([0.0 for f in self.foot_list], dtype=np.float32)
|
||||
self.ground_ids = set([(self.parts[f].bodies[self.parts[f].bodyIndex], self.parts[f].bodyPartIndex) for f in self.foot_ground_object_names])
|
||||
self.scene.actor_introduce(self)
|
||||
self.initial_z = None
|
||||
|
||||
def move_robot(self, init_x, init_y, init_z):
|
||||
"Used by multiplayer stadium to move sideways, to another running lane."
|
||||
self.cpp_robot.query_position()
|
||||
pose = self.cpp_robot.root_part.pose()
|
||||
pose.move_xyz(init_x, init_y, init_z) # Works because robot loads around (0,0,0), and some robots have z != 0 that is left intact
|
||||
self.cpp_robot.set_pose(pose)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
for n,j in enumerate(self.ordered_joints):
|
||||
j.set_motor_torque( self.power*j.power_coef*float(np.clip(a[n], -1, +1)) )
|
||||
|
||||
def calc_state(self):
|
||||
j = np.array([j.current_relative_position() for j in self.ordered_joints], dtype=np.float32).flatten()
|
||||
# even elements [0::2] position, scaled to -1..+1 between limits
|
||||
# odd elements [1::2] angular speed, scaled to show -1..+1
|
||||
self.joint_speeds = j[1::2]
|
||||
self.joints_at_limit = np.count_nonzero(np.abs(j[0::2]) > 0.99)
|
||||
|
||||
body_pose = self.robot_body.pose()
|
||||
parts_xyz = np.array( [p.pose().xyz() for p in self.parts.values()] ).flatten()
|
||||
self.body_xyz = (parts_xyz[0::3].mean(), parts_xyz[1::3].mean(), body_pose.xyz()[2]) # torso z is more informative than mean z
|
||||
self.body_rpy = body_pose.rpy()
|
||||
z = self.body_xyz[2]
|
||||
r, p, yaw = self.body_rpy
|
||||
if self.initial_z==None:
|
||||
self.initial_z = z
|
||||
self.walk_target_theta = np.arctan2( self.walk_target_y - self.body_xyz[1], self.walk_target_x - self.body_xyz[0] )
|
||||
self.walk_target_dist = np.linalg.norm( [self.walk_target_y - self.body_xyz[1], self.walk_target_x - self.body_xyz[0]] )
|
||||
angle_to_target = self.walk_target_theta - yaw
|
||||
|
||||
rot_speed = np.array(
|
||||
[[np.cos(-yaw), -np.sin(-yaw), 0],
|
||||
[np.sin(-yaw), np.cos(-yaw), 0],
|
||||
[ 0, 0, 1]]
|
||||
)
|
||||
vx, vy, vz = np.dot(rot_speed, self.robot_body.speed()) # rotate speed back to body point of view
|
||||
|
||||
more = np.array([
|
||||
z-self.initial_z,
|
||||
np.sin(angle_to_target), np.cos(angle_to_target),
|
||||
0.3*vx, 0.3*vy, 0.3*vz, # 0.3 is just scaling typical speed into -1..+1, no physical sense here
|
||||
r, p], dtype=np.float32)
|
||||
return np.clip( np.concatenate([more] + [j] + [self.feet_contact]), -5, +5)
|
||||
|
||||
def calc_potential(self):
|
||||
# progress in potential field is speed*dt, typical speed is about 2-3 meter per second, this potential will change 2-3 per frame (not per second),
|
||||
# all rewards have rew/frame units and close to 1.0
|
||||
return - self.walk_target_dist / self.scene.dt
|
||||
|
||||
electricity_cost = -2.0 # cost for using motors -- this parameter should be carefully tuned against reward for making progress, other values less improtant
|
||||
stall_torque_cost = -0.1 # cost for running electric current through a motor even at zero rotational speed, small
|
||||
foot_collision_cost = -1.0 # touches another leg, or other objects, that cost makes robot avoid smashing feet into itself
|
||||
foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
|
||||
joints_at_limit_cost = -0.1 # discourage stuck joints
|
||||
|
||||
def _step(self, a):
|
||||
if not self.scene.multiplayer: # if multiplayer, action first applied to all robots, then global step() called, then _step() for all robots with the same actions
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
|
||||
state = self.calc_state() # also calculates self.joints_at_limit
|
||||
|
||||
alive = float(self.alive_bonus(state[0]+self.initial_z, self.body_rpy[1])) # state[0] is body height above ground, body_rpy[1] is pitch
|
||||
done = alive < 0
|
||||
if not np.isfinite(state).all():
|
||||
print("~INF~", state)
|
||||
done = True
|
||||
|
||||
potential_old = self.potential
|
||||
self.potential = self.calc_potential()
|
||||
progress = float(self.potential - potential_old)
|
||||
|
||||
feet_collision_cost = 0.0
|
||||
for i,f in enumerate(self.feet):
|
||||
contact_ids = set((x[2], x[4]) for x in f.contact_list())
|
||||
#print("CONTACT OF '%s' WITH %s" % (f.name, ",".join(contact_names)) )
|
||||
self.feet_contact[i] = 1.0 if (self.ground_ids & contact_ids) else 0.0
|
||||
if contact_ids - self.ground_ids:
|
||||
feet_collision_cost += self.foot_collision_cost
|
||||
|
||||
electricity_cost = self.electricity_cost * float(np.abs(a*self.joint_speeds).mean()) # let's assume we have DC motor with controller, and reverse current braking
|
||||
electricity_cost += self.stall_torque_cost * float(np.square(a).mean())
|
||||
|
||||
joints_at_limit_cost = float(self.joints_at_limit_cost * self.joints_at_limit)
|
||||
|
||||
self.rewards = [
|
||||
alive,
|
||||
progress,
|
||||
electricity_cost,
|
||||
joints_at_limit_cost,
|
||||
feet_collision_cost
|
||||
]
|
||||
|
||||
self.HUD(state, a, done)
|
||||
return state, sum(self.rewards), bool(done), {}
|
||||
|
||||
def camera_adjust(self):
|
||||
x, y, z = self.body_xyz
|
||||
self.camera_x = 0.98*self.camera_x + (1-0.98)*x
|
||||
self.camera.move_and_look_at(self.camera_x, y-2.0, 1.4, x, y, 1.0)
|
||||
|
||||
class PybulletHopper(PybulletForwardWalkersBase):
|
||||
foot_list = ["foot"]
|
||||
def __init__(self):
|
||||
PybulletForwardWalkersBase.__init__(self, "hopper.xml", "torso", action_dim=3, obs_dim=15, power=0.75)
|
||||
def alive_bonus(self, z, pitch):
|
||||
return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
|
||||
|
||||
class PybulletWalker2d(PybulletForwardWalkersBase):
|
||||
foot_list = ["foot", "foot_left"]
|
||||
def __init__(self):
|
||||
PybulletForwardWalkersBase.__init__(self, "walker2d.xml", "torso", action_dim=6, obs_dim=22, power=0.40)
|
||||
def alive_bonus(self, z, pitch):
|
||||
return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
|
||||
def robot_specific_reset(self):
|
||||
PybulletForwardWalkersBase.robot_specific_reset(self)
|
||||
for n in ["foot_joint", "foot_left_joint"]:
|
||||
self.jdict[n].power_coef = 30.0
|
||||
|
||||
class PybulletHalfCheetah(PybulletForwardWalkersBase):
|
||||
foot_list = ["ffoot", "fshin", "fthigh", "bfoot", "bshin", "bthigh"] # track these contacts with ground
|
||||
def __init__(self):
|
||||
PybulletForwardWalkersBase.__init__(self, "half_cheetah.xml", "torso", action_dim=6, obs_dim=26, power=0.90)
|
||||
def alive_bonus(self, z, pitch):
|
||||
# Use contact other than feet to terminate episode: due to a lot of strange walks using knees
|
||||
return +1 if np.abs(pitch) < 1.0 and not self.feet_contact[1] and not self.feet_contact[2] and not self.feet_contact[4] and not self.feet_contact[5] else -1
|
||||
def robot_specific_reset(self):
|
||||
PybulletForwardWalkersBase.robot_specific_reset(self)
|
||||
self.jdict["bthigh"].power_coef = 120.0
|
||||
self.jdict["bshin"].power_coef = 90.0
|
||||
self.jdict["bfoot"].power_coef = 60.0
|
||||
self.jdict["fthigh"].power_coef = 140.0
|
||||
self.jdict["fshin"].power_coef = 60.0
|
||||
self.jdict["ffoot"].power_coef = 30.0
|
||||
|
||||
class PybulletAnt(PybulletForwardWalkersBase):
|
||||
foot_list = ['front_left_foot', 'front_right_foot', 'left_back_foot', 'right_back_foot']
|
||||
def __init__(self):
|
||||
PybulletForwardWalkersBase.__init__(self, "ant.xml", "torso", action_dim=8, obs_dim=28, power=10.5)
|
||||
def alive_bonus(self, z, pitch):
|
||||
return +1 if z > 0.26 else -1 # 0.25 is central sphere rad, die if it scrapes the ground
|
||||
|
||||
|
||||
## 3d Humanoid ##
|
||||
|
||||
class PybulletHumanoid(PybulletForwardWalkersBase):
|
||||
self_collision = True
|
||||
foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
|
||||
|
||||
def __init__(self):
|
||||
PybulletForwardWalkersBase.__init__(self, 'humanoid_symmetric.xml', 'torso', action_dim=17, obs_dim=44, power=0.41)
|
||||
# 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25
|
||||
self.electricity_cost = 4.25*PybulletForwardWalkersBase.electricity_cost
|
||||
self.stall_torque_cost = 4.25*PybulletForwardWalkersBase.stall_torque_cost
|
||||
|
||||
def robot_specific_reset(self):
|
||||
PybulletForwardWalkersBase.robot_specific_reset(self)
|
||||
self.motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"]
|
||||
self.motor_power = [100, 100, 100]
|
||||
self.motor_names += ["right_hip_x", "right_hip_z", "right_hip_y", "right_knee"]
|
||||
self.motor_power += [100, 100, 300, 200]
|
||||
self.motor_names += ["left_hip_x", "left_hip_z", "left_hip_y", "left_knee"]
|
||||
self.motor_power += [100, 100, 300, 200]
|
||||
self.motor_names += ["right_shoulder1", "right_shoulder2", "right_elbow"]
|
||||
self.motor_power += [75, 75, 75]
|
||||
self.motor_names += ["left_shoulder1", "left_shoulder2", "left_elbow"]
|
||||
self.motor_power += [75, 75, 75]
|
||||
self.motors = [self.jdict[n] for n in self.motor_names]
|
||||
# if self.random_yaw: # TODO: Make leaning work as soon as the rest works
|
||||
# cpose = cpp_household.Pose()
|
||||
# yaw = self.np_random.uniform(low=-3.14, high=3.14)
|
||||
# if self.random_lean and self.np_random.randint(2)==0:
|
||||
# cpose.set_xyz(0, 0, 1.4)
|
||||
# if self.np_random.randint(2)==0:
|
||||
# pitch = np.pi/2
|
||||
# cpose.set_xyz(0, 0, 0.45)
|
||||
# else:
|
||||
# pitch = np.pi*3/2
|
||||
# cpose.set_xyz(0, 0, 0.25)
|
||||
# roll = 0
|
||||
# cpose.set_rpy(roll, pitch, yaw)
|
||||
# else:
|
||||
# cpose.set_xyz(0, 0, 1.4)
|
||||
# cpose.set_rpy(0, 0, yaw) # just face random direction, but stay straight otherwise
|
||||
# self.cpp_robot.set_pose_and_speed(cpose, 0,0,0)
|
||||
self.initial_z = 0.8
|
||||
|
||||
random_yaw = False
|
||||
random_lean = False
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
force_gain = 1
|
||||
for i, m, power in zip(range(17), self.motors, self.motor_power):
|
||||
m.set_motor_torque( float(force_gain * power*self.power*a[i]) )
|
||||
#m.set_motor_torque(float(force_gain * power * self.power * np.clip(a[i], -1, +1)))
|
||||
|
||||
def alive_bonus(self, z, pitch):
|
||||
return +2 if z > 0.78 else -1 # 2 here because 17 joints produce a lot of electricity cost just from policy noise, living must be better than dying
|
||||
|
||||
304
examples/pybullet/gym/envs/gym_manipulators.py
Normal file
304
examples/pybullet/gym/envs/gym_manipulators.py
Normal file
@@ -0,0 +1,304 @@
|
||||
from pybulletgym.envs.scene_abstract import SingleRobotEmptyScene
|
||||
from gym_mujoco_xml_env import PybulletMujocoXmlEnv
|
||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||
import numpy as np
|
||||
import os, sys
|
||||
|
||||
class PybulletReacher(PybulletMujocoXmlEnv):
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'reacher.xml', 'body0', action_dim=2, obs_dim=9)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=0.0, timestep=0.0165, frame_skip=1)
|
||||
|
||||
TARG_LIMIT = 0.27
|
||||
def robot_specific_reset(self):
|
||||
self.jdict["target_x"].reset_current_position(self.np_random.uniform( low=-self.TARG_LIMIT, high=self.TARG_LIMIT ), 0)
|
||||
self.jdict["target_y"].reset_current_position(self.np_random.uniform( low=-self.TARG_LIMIT, high=self.TARG_LIMIT ), 0)
|
||||
self.fingertip = self.parts["fingertip"]
|
||||
self.target = self.parts["target"]
|
||||
self.central_joint = self.jdict["joint0"]
|
||||
self.elbow_joint = self.jdict["joint1"]
|
||||
self.central_joint.reset_current_position(self.np_random.uniform( low=-3.14, high=3.14 ), 0)
|
||||
self.elbow_joint.reset_current_position(self.np_random.uniform( low=-3.14, high=3.14 ), 0)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
self.central_joint.set_motor_torque( 0.05*float(np.clip(a[0], -1, +1)) )
|
||||
self.elbow_joint.set_motor_torque( 0.05*float(np.clip(a[1], -1, +1)) )
|
||||
|
||||
def calc_state(self):
|
||||
theta, self.theta_dot = self.central_joint.current_relative_position()
|
||||
self.gamma, self.gamma_dot = self.elbow_joint.current_relative_position()
|
||||
target_x, _ = self.jdict["target_x"].current_position()
|
||||
target_y, _ = self.jdict["target_y"].current_position()
|
||||
self.to_target_vec = np.array(self.fingertip.pose().xyz()) - np.array(self.target.pose().xyz())
|
||||
return np.array([
|
||||
target_x,
|
||||
target_y,
|
||||
self.to_target_vec[0],
|
||||
self.to_target_vec[1],
|
||||
np.cos(theta),
|
||||
np.sin(theta),
|
||||
self.theta_dot,
|
||||
self.gamma,
|
||||
self.gamma_dot,
|
||||
])
|
||||
|
||||
def calc_potential(self):
|
||||
return -100 * np.linalg.norm(self.to_target_vec)
|
||||
|
||||
def _step(self, a):
|
||||
assert(not self.scene.multiplayer)
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
|
||||
state = self.calc_state() # sets self.to_target_vec
|
||||
|
||||
potential_old = self.potential
|
||||
self.potential = self.calc_potential()
|
||||
|
||||
electricity_cost = (
|
||||
-0.10*(np.abs(a[0]*self.theta_dot) + np.abs(a[1]*self.gamma_dot)) # work torque*angular_velocity
|
||||
-0.01*(np.abs(a[0]) + np.abs(a[1])) # stall torque require some energy
|
||||
)
|
||||
stuck_joint_cost = -0.1 if np.abs(np.abs(self.gamma)-1) < 0.01 else 0.0
|
||||
self.rewards = [float(self.potential - potential_old), float(electricity_cost), float(stuck_joint_cost)]
|
||||
self.HUD(state, a, False)
|
||||
return state, sum(self.rewards), False, {}
|
||||
|
||||
def camera_adjust(self):
|
||||
x, y, z = self.fingertip.pose().xyz()
|
||||
x *= 0.5
|
||||
y *= 0.5
|
||||
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
||||
|
||||
|
||||
class PybulletPusher(PybulletMujocoXmlEnv):
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'pusher.xml', 'body0', action_dim=7, obs_dim=5)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def robot_specific_reset(self):
|
||||
self.fingertip = self.parts["fingertip"]
|
||||
# qpos = self.init_qpos
|
||||
|
||||
self.goal_pos = np.asarray([0, 0])
|
||||
while True:
|
||||
self.cylinder_pos = np.concatenate([
|
||||
self.np_random.uniform(low=-0.3, high=0, size=1),
|
||||
self.np_random.uniform(low=-0.2, high=0.2, size=1)])
|
||||
if np.linalg.norm(self.cylinder_pos - self.goal_pos) > 0.17:
|
||||
break
|
||||
|
||||
# This is probably position setting
|
||||
# qpos[-4:-2] = self.cylinder_pos
|
||||
# qpos[-2:] = self.goal_pos
|
||||
# qvel = self.init_qvel + self.np_random.uniform(low=-0.005,
|
||||
# high=0.005, size=self.model.nv)
|
||||
# qvel[-4:] = 0
|
||||
# self.set_state(qpos, qvel)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
|
||||
def calc_state(self):
|
||||
return np.concatenate([
|
||||
np.array([j.current_position() for j in self.ordered_joints]).flatten(), # position
|
||||
np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # speed
|
||||
self.parts["fingertip"].pose().xyz(),
|
||||
self.parts["object"].pose().xyz(),
|
||||
self.parts["goal"].pose().xyz(),
|
||||
])
|
||||
|
||||
def _step(self, a):
|
||||
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
|
||||
state = self.calc_state()
|
||||
|
||||
reward_near_vec = self.parts["object"].pose().xyz() - self.parts["fingertip"].pose().xyz()
|
||||
reward_dist_vec = self.parts["object"].pose().xyz() - self.parts["goal"].pose().xyz()
|
||||
|
||||
reward_near = - np.linalg.norm(reward_near_vec)
|
||||
reward_dist = - np.linalg.norm(reward_dist_vec)
|
||||
reward_ctrl = - np.square(a).sum()
|
||||
reward = reward_dist + 0.1 * reward_ctrl + 0.5 * reward_near
|
||||
|
||||
done = False
|
||||
return state, reward, done, dict(reward_dist=reward_dist, reward_ctrl=reward_ctrl)
|
||||
|
||||
def camera_adjust(self):
|
||||
x, y, z = self.fingertip.pose().xyz()
|
||||
x *= 0.5
|
||||
y *= 0.5
|
||||
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
||||
|
||||
|
||||
class PybulletStriker(PybulletMujocoXmlEnv):
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'striker.xml', 'body0', action_dim=7, obs_dim=5)
|
||||
self._striked = False
|
||||
self._min_strike_dist = np.inf
|
||||
self.strike_threshold = 0.1
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def robot_specific_reset(self):
|
||||
self.fingertip = self.parts["fingertip"]
|
||||
self._min_strike_dist = np.inf
|
||||
self._striked = False
|
||||
self._strike_pos = None
|
||||
|
||||
# reset position of manipulator
|
||||
for j in self.ordered_joints:
|
||||
j.reset_current_position(self.np_random.uniform( low=-0.1, high=0.1 ))
|
||||
|
||||
# reset speed of manipulator
|
||||
|
||||
# reset ball position
|
||||
|
||||
# qpos = self.init_qpos
|
||||
|
||||
self.ball = np.array([0.5, -0.175])
|
||||
|
||||
while True:
|
||||
self.goal = np.concatenate([
|
||||
self.np_random.uniform(low=0.15, high=0.7, size=1),
|
||||
self.np_random.uniform(low=0.1, high=1.0, size=1)])
|
||||
if np.linalg.norm(self.ball - self.goal) > 0.17:
|
||||
break
|
||||
# This is probably position setting
|
||||
# qpos[-9:-7] = [self.ball[1], self.ball[0]]
|
||||
# qpos[-7:-5] = self.goal
|
||||
# diff = self.ball - self.goal
|
||||
# angle = -np.arctan(diff[0] / (diff[1] + 1e-8))
|
||||
# qpos[-1] = angle / 3.14
|
||||
# qvel = self.init_qvel + self.np_random.uniform(low=-.1, high=.1,
|
||||
# size=self.model.nv)
|
||||
# qvel[7:] = 0
|
||||
# self.set_state(qpos, qvel)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
|
||||
def calc_state(self):
|
||||
return np.concatenate([
|
||||
np.array([j.current_position() for j in self.ordered_joints]).flatten(), # position
|
||||
np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # speed
|
||||
self.parts["fingertip"].pose().xyz(),
|
||||
self.parts["object"].pose().xyz(),
|
||||
self.parts["goal"].pose().xyz(),
|
||||
])
|
||||
|
||||
def _step(self, a):
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
state = self.calc_state()
|
||||
|
||||
dist_object_finger = self.parts["object"].pose().xyz() - self.parts["fingertip"].pose().xyz()
|
||||
reward_dist_vec = self.parts["object"].pose().xyz() - self.parts["goal"].pose().xyz()
|
||||
|
||||
self._min_strike_dist = min(self._min_strike_dist, np.linalg.norm(reward_dist_vec))
|
||||
|
||||
if np.linalg.norm(dist_object_finger) < self.strike_threshold:
|
||||
self._striked = True
|
||||
self._strike_pos = self.parts["fingertip"].pose().xyz()
|
||||
|
||||
if self._striked:
|
||||
reward_near_vec = self.parts["object"].pose().xyz() - self._strike_pos
|
||||
else:
|
||||
reward_near_vec = self.parts["object"].pose().xyz() - self.parts["fingertip"].pose().xyz()
|
||||
|
||||
reward_near = - np.linalg.norm(reward_near_vec)
|
||||
|
||||
reward_dist = - np.linalg.norm(self._min_strike_dist)
|
||||
reward_ctrl = - np.square(a).sum()
|
||||
reward = 3 * reward_dist + 0.1 * reward_ctrl + 0.5 * reward_near
|
||||
|
||||
done = False
|
||||
return state, reward, done, dict(reward_dist=reward_dist, reward_ctrl=reward_ctrl)
|
||||
|
||||
def camera_adjust(self):
|
||||
x, y, z = self.fingertip.pose().xyz()
|
||||
x *= 0.5
|
||||
y *= 0.5
|
||||
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
||||
|
||||
|
||||
class PybulletThrower(PybulletMujocoXmlEnv):
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'thrower.xml', 'body0', action_dim=7, obs_dim=5)
|
||||
self._ball_hit_ground = False
|
||||
self._ball_hit_location = None
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=0.0, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def robot_specific_reset(self):
|
||||
self.fingertip = self.parts["fingertip"]
|
||||
self._ball_hit_ground = False
|
||||
self._ball_hit_location = None
|
||||
|
||||
# reset position of manipulator
|
||||
for j in self.ordered_joints:
|
||||
j.reset_current_position(self.np_random.uniform( low=-0.1, high=0.1 ))
|
||||
|
||||
# reset speed of manipulator
|
||||
# This is probably position setting
|
||||
# qpos = self.init_qpos
|
||||
# self.goal = np.array([self.np_random.uniform(low=-0.3, high=0.3),
|
||||
# self.np_random.uniform(low=-0.3, high=0.3)])
|
||||
#
|
||||
# qpos[-9:-7] = self.goal
|
||||
# qvel = self.init_qvel + self.np_random.uniform(low=-0.005,
|
||||
# high=0.005, size=self.model.nv)
|
||||
# qvel[7:] = 0
|
||||
# self.set_state(qpos, qvel)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
|
||||
def calc_state(self):
|
||||
return np.concatenate([
|
||||
np.array([j.current_position() for j in self.ordered_joints]).flatten(), # position
|
||||
np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # speed
|
||||
self.parts["fingertip"].pose().xyz(),
|
||||
self.parts["ball"].pose().xyz(),
|
||||
self.parts["goal"].pose().xyz(),
|
||||
])
|
||||
|
||||
def _step(self, a):
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
state = self.calc_state()
|
||||
|
||||
ball_xy = self.parts["ball"].pose().xyz()[:2]
|
||||
goal_xy = self.parts["goal"].pose().xyz()[:2]
|
||||
|
||||
if not self._ball_hit_ground and self.parts["ball"].pose().xyz()[2] < -0.25:
|
||||
self._ball_hit_ground = True
|
||||
self._ball_hit_location = self.parts["ball"].pose().xyz()
|
||||
|
||||
if self._ball_hit_ground:
|
||||
ball_hit_xy = self._ball_hit_location[:2]
|
||||
reward_dist = -np.linalg.norm(ball_hit_xy - goal_xy)
|
||||
else:
|
||||
reward_dist = -np.linalg.norm(ball_xy - goal_xy)
|
||||
reward_ctrl = - np.square(a).sum()
|
||||
|
||||
reward = reward_dist + 0.002 * reward_ctrl
|
||||
|
||||
done = False
|
||||
return state, reward, done, dict(reward_dist=reward_dist, reward_ctrl=reward_ctrl)
|
||||
|
||||
def camera_adjust(self):
|
||||
x, y, z = self.fingertip.pose().xyz()
|
||||
x *= 0.5
|
||||
y *= 0.5
|
||||
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
||||
|
||||
246
examples/pybullet/gym/envs/gym_mujoco_xml_env.py
Normal file
246
examples/pybullet/gym/envs/gym_mujoco_xml_env.py
Normal file
@@ -0,0 +1,246 @@
|
||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import os
|
||||
|
||||
|
||||
class PybulletMujocoXmlEnv(gym.Env):
|
||||
"""
|
||||
Base class for MuJoCo .xml actors in a Scene.
|
||||
These environments create single-player scenes and behave like normal Gym environments, if
|
||||
you don't use multiplayer.
|
||||
"""
|
||||
|
||||
metadata = {
|
||||
'render.modes': ['human', 'rgb_array'],
|
||||
'video.frames_per_second': 60
|
||||
}
|
||||
|
||||
self_collision = False
|
||||
|
||||
def __init__(self, model_xml, robot_name, action_dim, obs_dim):
|
||||
self.scene = None
|
||||
|
||||
self.parts = None
|
||||
self.jdict = None
|
||||
self.ordered_joints = None
|
||||
self.robot_body = None
|
||||
|
||||
high = np.ones([action_dim])
|
||||
self.action_space = gym.spaces.Box(-high, high)
|
||||
high = np.inf*np.ones([obs_dim])
|
||||
self.observation_space = gym.spaces.Box(-high, high)
|
||||
self._seed()
|
||||
|
||||
self.model_xml = model_xml
|
||||
self.robot_name = robot_name
|
||||
|
||||
self.camera = Camera()
|
||||
|
||||
def _seed(self, seed=None):
|
||||
self.np_random, seed = gym.utils.seeding.np_random(seed)
|
||||
return [seed]
|
||||
|
||||
def addToScene(self, bodies):
|
||||
if self.parts is not None:
|
||||
parts = self.parts
|
||||
else:
|
||||
parts = {}
|
||||
|
||||
if self.jdict is not None:
|
||||
joints = self.jdict
|
||||
else:
|
||||
joints = {}
|
||||
|
||||
if self.ordered_joints is not None:
|
||||
ordered_joints = self.ordered_joints
|
||||
else:
|
||||
ordered_joints = []
|
||||
|
||||
dump = 0
|
||||
for i in range(len(bodies)):
|
||||
if p.getNumJoints(bodies[i]) == 0:
|
||||
part_name, robot_name = p.getBodyInfo(bodies[i], 0)
|
||||
robot_name = robot_name.decode("utf8")
|
||||
part_name = part_name.decode("utf8")
|
||||
parts[part_name] = BodyPart(part_name, bodies, i, -1)
|
||||
for j in range(p.getNumJoints(bodies[i])):
|
||||
_,joint_name,_,_,_,_,_,_,_,_,_,_,part_name = p.getJointInfo(bodies[i], j)
|
||||
|
||||
joint_name = joint_name.decode("utf8")
|
||||
part_name = part_name.decode("utf8")
|
||||
|
||||
if dump: print("ROBOT PART '%s'" % part_name)
|
||||
if dump: print("ROBOT JOINT '%s'" % joint_name) # limits = %+0.2f..%+0.2f effort=%0.3f speed=%0.3f" % ((joint_name,) + j.limits()) )
|
||||
|
||||
parts[part_name] = BodyPart(part_name, bodies, i, j)
|
||||
|
||||
if part_name == self.robot_name:
|
||||
self.robot_body = parts[part_name]
|
||||
|
||||
if i == 0 and j == 0 and self.robot_body is None: # if nothing else works, we take this as robot_body
|
||||
parts[self.robot_name] = BodyPart(self.robot_name, bodies, 0, -1)
|
||||
self.robot_body = parts[self.robot_name]
|
||||
|
||||
if joint_name[:6] == "ignore":
|
||||
Joint(joint_name, bodies, i, j).disable_motor()
|
||||
continue
|
||||
|
||||
if joint_name[:8] != "jointfix":
|
||||
joints[joint_name] = Joint(joint_name, bodies, i, j)
|
||||
ordered_joints.append(joints[joint_name])
|
||||
|
||||
joints[joint_name].power_coef = 100.0
|
||||
|
||||
return parts, joints, ordered_joints, self.robot_body
|
||||
|
||||
def _reset(self):
|
||||
if self.scene is None:
|
||||
self.scene = self.create_single_player_scene()
|
||||
if not self.scene.multiplayer:
|
||||
self.scene.episode_restart()
|
||||
|
||||
self.ordered_joints = []
|
||||
self.frame = 0
|
||||
self.done = 0
|
||||
self.reward = 0
|
||||
dump = 0
|
||||
|
||||
if self.self_collision:
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(p.loadMJCF(os.path.join(os.path.dirname(__file__), "mujoco_assets", self.model_xml), flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS))
|
||||
else:
|
||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(p.loadMJCF(os.path.join(os.path.dirname(__file__), "mujoco_assets", self.model_xml)))
|
||||
|
||||
self.robot_specific_reset()
|
||||
s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
|
||||
self.potential = self.calc_potential()
|
||||
return s
|
||||
|
||||
def _render(self, mode, close):
|
||||
pass
|
||||
|
||||
def calc_potential(self):
|
||||
return 0
|
||||
|
||||
def HUD(self, state, a, done):
|
||||
pass
|
||||
|
||||
class Camera:
|
||||
def __init__(self):
|
||||
pass
|
||||
|
||||
def move_and_look_at(self,i,j,k,x,y,z):
|
||||
lookat = [x,y,z]
|
||||
distance = 10
|
||||
yaw = 10
|
||||
p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)
|
||||
|
||||
class Pose_Helper: # dummy class to comply to original interface
|
||||
def __init__(self, body_part):
|
||||
self.body_part = body_part
|
||||
|
||||
def xyz(self):
|
||||
return self.body_part.current_position()
|
||||
|
||||
def rpy(self):
|
||||
return p.getEulerFromQuaternion(self.body_part.current_orientation())
|
||||
|
||||
def orientation(self):
|
||||
return self.body_part.current_orientation()
|
||||
|
||||
class BodyPart:
|
||||
def __init__(self, body_name, bodies, bodyIndex, bodyPartIndex):
|
||||
self.bodies = bodies
|
||||
self.bodyIndex = bodyIndex
|
||||
self.bodyPartIndex = bodyPartIndex
|
||||
self.initialPosition = self.current_position()
|
||||
self.initialOrientation = self.current_orientation()
|
||||
self.bp_pose = Pose_Helper(self)
|
||||
|
||||
def state_fields_of_pose_of(self, body_id, link_id=-1): # a method you will most probably need a lot to get pose and orientation
|
||||
if link_id == -1:
|
||||
(x, y, z), (a, b, c, d) = p.getBasePositionAndOrientation(body_id)
|
||||
else:
|
||||
(x, y, z), (a, b, c, d), _, _, _, _ = p.getLinkState(body_id, link_id)
|
||||
return np.array([x, y, z, a, b, c, d])
|
||||
|
||||
def get_pose(self):
|
||||
return self.state_fields_of_pose_of(self.bodies[self.bodyIndex], self.bodyPartIndex)
|
||||
|
||||
def speed(self):
|
||||
if self.bodyPartIndex == -1:
|
||||
(vx, vy, vz), _ = p.getBaseVelocity(self.bodies[self.bodyIndex])
|
||||
else:
|
||||
(x,y,z), (a,b,c,d), _,_,_,_, (vx, vy, vz), (vr,vp,vy) = p.getLinkState(self.bodies[self.bodyIndex], self.bodyPartIndex, computeLinkVelocity=1)
|
||||
return np.array([vx, vy, vz])
|
||||
|
||||
def current_position(self):
|
||||
return self.get_pose()[:3]
|
||||
|
||||
def current_orientation(self):
|
||||
return self.get_pose()[3:]
|
||||
|
||||
def reset_position(self, position):
|
||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, self.get_orientation())
|
||||
|
||||
def reset_orientation(self, orientation):
|
||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
|
||||
|
||||
def reset_pose(self, position, orientation):
|
||||
p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
|
||||
|
||||
def pose(self):
|
||||
return self.bp_pose
|
||||
|
||||
def contact_list(self):
|
||||
return p.getContactPoints(self.bodies[self.bodyIndex], -1, self.bodyPartIndex, -1)
|
||||
|
||||
|
||||
class Joint:
|
||||
def __init__(self, joint_name, bodies, bodyIndex, jointIndex):
|
||||
self.bodies = bodies
|
||||
self.bodyIndex = bodyIndex
|
||||
self.jointIndex = jointIndex
|
||||
self.joint_name = joint_name
|
||||
_,_,_,_,_,_,_,_,self.lowerLimit, self.upperLimit,_,_,_ = p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
|
||||
self.power_coeff = 0
|
||||
|
||||
def set_state(self, x, vx):
|
||||
p.resetJointState(self.bodies[self.bodyIndex], self.jointIndex, x, vx)
|
||||
|
||||
def current_position(self): # just some synonyme method
|
||||
return self.get_state()
|
||||
|
||||
def current_relative_position(self):
|
||||
pos, vel = self.get_state()
|
||||
pos_mid = 0.5 * (self.lowerLimit + self.upperLimit);
|
||||
return (
|
||||
2 * (pos - pos_mid) / (self.upperLimit - self.lowerLimit),
|
||||
0.1 * vel
|
||||
)
|
||||
|
||||
def get_state(self):
|
||||
x, vx,_,_ = p.getJointState(self.bodies[self.bodyIndex],self.jointIndex)
|
||||
return x, vx
|
||||
|
||||
def set_position(self, position):
|
||||
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,p.POSITION_CONTROL, targetPosition=position)
|
||||
|
||||
def set_velocity(self, velocity):
|
||||
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,p.VELOCITY_CONTROL, targetVelocity=velocity)
|
||||
|
||||
def set_motor_torque(self, torque): # just some synonyme method
|
||||
self.set_torque(torque)
|
||||
|
||||
def set_torque(self, torque):
|
||||
p.setJointMotorControl2(bodyIndex=self.bodies[self.bodyIndex], jointIndex=self.jointIndex, controlMode=p.TORQUE_CONTROL, force=torque) #, positionGain=0.1, velocityGain=0.1)
|
||||
|
||||
def reset_current_position(self, position, velocity): # just some synonyme method
|
||||
self.reset_position(position, velocity)
|
||||
|
||||
def reset_position(self, position, velocity):
|
||||
p.resetJointState(self.bodies[self.bodyIndex],self.jointIndex,targetValue=position, targetVelocity=velocity)
|
||||
self.disable_motor()
|
||||
|
||||
def disable_motor(self):
|
||||
p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,controlMode=p.VELOCITY_CONTROL, force=0)
|
||||
133
examples/pybullet/gym/envs/gym_pendula.py
Normal file
133
examples/pybullet/gym/envs/gym_pendula.py
Normal file
@@ -0,0 +1,133 @@
|
||||
from pybulletgym.envs.scene_abstract import SingleRobotEmptyScene
|
||||
from gym_mujoco_xml_env import PybulletMujocoXmlEnv
|
||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||
import numpy as np
|
||||
import os, sys
|
||||
|
||||
class PybulletInvertedPendulum(PybulletMujocoXmlEnv):
|
||||
swingup = False
|
||||
force_gain = 12 # TODO: Try to find out why we need to scale the force
|
||||
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'inverted_pendulum.xml', 'cart', action_dim=1, obs_dim=5)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)
|
||||
|
||||
def robot_specific_reset(self):
|
||||
self.pole = self.parts["pole"]
|
||||
self.slider = self.jdict["slider"]
|
||||
self.j1 = self.jdict["hinge"]
|
||||
u = self.np_random.uniform(low=-.1, high=.1)
|
||||
self.j1.reset_current_position( u if not self.swingup else 3.1415+u , 0)
|
||||
self.j1.set_motor_torque(0)
|
||||
|
||||
def apply_action(self, a):
|
||||
#assert( np.isfinite(a).all() )
|
||||
if not np.isfinite(a).all():
|
||||
print("a is inf")
|
||||
a[0] = 0
|
||||
self.slider.set_motor_torque( self.force_gain * 100*float(np.clip(a[0], -1, +1)) )
|
||||
|
||||
def calc_state(self):
|
||||
self.theta, theta_dot = self.j1.current_position()
|
||||
x, vx = self.slider.current_position()
|
||||
#assert( np.isfinite(x) )
|
||||
|
||||
if not np.isfinite(x):
|
||||
print("x is inf")
|
||||
x = 0
|
||||
|
||||
if not np.isfinite(vx):
|
||||
print("vx is inf")
|
||||
vx = 0
|
||||
|
||||
if not np.isfinite(self.theta):
|
||||
print("theta is inf")
|
||||
self.theta = 0
|
||||
|
||||
if not np.isfinite(theta_dot):
|
||||
print("theta_dot is inf")
|
||||
theta_dot = 0
|
||||
|
||||
return np.array([
|
||||
x, vx,
|
||||
np.cos(self.theta), np.sin(self.theta), theta_dot
|
||||
])
|
||||
|
||||
def _step(self, a):
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
state = self.calc_state() # sets self.pos_x self.pos_y
|
||||
vel_penalty = 0
|
||||
if self.swingup:
|
||||
reward = np.cos(self.theta)
|
||||
done = False
|
||||
else:
|
||||
reward = 1.0
|
||||
done = np.abs(self.theta) > .2
|
||||
self.rewards = [float(reward)]
|
||||
self.HUD(state, a, done)
|
||||
return state, sum(self.rewards), done, {}
|
||||
|
||||
def camera_adjust(self):
|
||||
self.camera.move_and_look_at(0,1.2,1.0, 0,0,0.5)
|
||||
|
||||
class PybulletInvertedPendulumSwingup(PybulletInvertedPendulum):
|
||||
swingup = True
|
||||
force_gain = 2.2 # TODO: Try to find out why we need to scale the force
|
||||
|
||||
class PybulletInvertedDoublePendulum(PybulletMujocoXmlEnv):
|
||||
def __init__(self):
|
||||
PybulletMujocoXmlEnv.__init__(self, 'inverted_double_pendulum.xml', 'cart', action_dim=1, obs_dim=9)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.8, timestep=0.0165, frame_skip=1)
|
||||
|
||||
def robot_specific_reset(self):
|
||||
self.pole2 = self.parts["pole2"]
|
||||
self.slider = self.jdict["slider"]
|
||||
self.j1 = self.jdict["hinge"]
|
||||
self.j2 = self.jdict["hinge2"]
|
||||
u = self.np_random.uniform(low=-.1, high=.1, size=[2])
|
||||
self.j1.reset_current_position(float(u[0]), 0)
|
||||
self.j2.reset_current_position(float(u[1]), 0)
|
||||
self.j1.set_motor_torque(0)
|
||||
self.j2.set_motor_torque(0)
|
||||
|
||||
def apply_action(self, a):
|
||||
assert( np.isfinite(a).all() )
|
||||
force_gain = 0.78 # TODO: Try to find out why we need to scale the force
|
||||
self.slider.set_motor_torque( force_gain *200*float(np.clip(a[0], -1, +1)) )
|
||||
|
||||
def calc_state(self):
|
||||
theta, theta_dot = self.j1.current_position()
|
||||
gamma, gamma_dot = self.j2.current_position()
|
||||
x, vx = self.slider.current_position()
|
||||
self.pos_x, _, self.pos_y = self.pole2.pose().xyz()
|
||||
assert( np.isfinite(x) )
|
||||
return np.array([
|
||||
x, vx,
|
||||
self.pos_x,
|
||||
np.cos(theta), np.sin(theta), theta_dot,
|
||||
np.cos(gamma), np.sin(gamma), gamma_dot,
|
||||
])
|
||||
|
||||
def _step(self, a):
|
||||
self.apply_action(a)
|
||||
self.scene.global_step()
|
||||
state = self.calc_state() # sets self.pos_x self.pos_y
|
||||
# upright position: 0.6 (one pole) + 0.6 (second pole) * 0.5 (middle of second pole) = 0.9
|
||||
# using <site> tag in original xml, upright position is 0.6 + 0.6 = 1.2, difference +0.3
|
||||
dist_penalty = 0.01 * self.pos_x ** 2 + (self.pos_y + 0.3 - 2) ** 2
|
||||
# v1, v2 = self.model.data.qvel[1:3] TODO when this fixed https://github.com/bulletphysics/bullet3/issues/1040
|
||||
#vel_penalty = 1e-3 * v1**2 + 5e-3 * v2**2
|
||||
vel_penalty = 0
|
||||
alive_bonus = 10
|
||||
done = self.pos_y + 0.3 <= 1
|
||||
self.rewards = [float(alive_bonus), float(-dist_penalty), float(-vel_penalty)]
|
||||
self.HUD(state, a, done)
|
||||
return state, sum(self.rewards), done, {}
|
||||
|
||||
def camera_adjust(self):
|
||||
self.camera.move_and_look_at(0,1.2,1.2, 0,0,0.5)
|
||||
28
examples/pybullet/gym/envs/kerasrl_utils.py
Normal file
28
examples/pybullet/gym/envs/kerasrl_utils.py
Normal file
@@ -0,0 +1,28 @@
|
||||
|
||||
import re
|
||||
from gym import error
|
||||
import glob
|
||||
# checkpoints/KerasDDPG-InvertedPendulum-v0-20170701190920_actor.h5
|
||||
weight_save_re = re.compile(r'^(?:\w+\/)+?(\w+-v\d+)-(\w+-v\d+)-(\d+)(?:_\w+)?\.(\w+)$')
|
||||
|
||||
def get_fields(weight_save_name):
|
||||
match = weight_save_re.search(weight_save_name)
|
||||
if not match:
|
||||
raise error.Error('Attempted to read a malformed weight save: {}. (Currently all weight saves must be of the form {}.)'.format(id,weight_save_re.pattern))
|
||||
return match.group(1), match.group(2), int(match.group(3))
|
||||
|
||||
def get_latest_save(file_folder, agent_name, env_name, version_number):
|
||||
"""
|
||||
Returns the properties of the latest weight save. The information can be used to generate the loading path
|
||||
:return:
|
||||
"""
|
||||
path = "%s%s"% (file_folder, "*.h5")
|
||||
file_list = glob.glob(path)
|
||||
latest_file_properties = []
|
||||
file_properties = []
|
||||
for f in file_list:
|
||||
file_properties = get_fields(f)
|
||||
if file_properties[0] == agent_name and file_properties[1] == env_name and (latest_file_properties == [] or file_properties[2] > latest_file_properties[2]):
|
||||
latest_file_properties = file_properties
|
||||
|
||||
return latest_file_properties
|
||||
71
examples/pybullet/gym/envs/mujoco_assets/ant.xml
Normal file
71
examples/pybullet/gym/envs/mujoco_assets/ant.xml
Normal file
@@ -0,0 +1,71 @@
|
||||
<mujoco model="ant">
|
||||
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/>
|
||||
<option integrator="RK4" timestep="0.01"/>
|
||||
<custom>
|
||||
<numeric data="0.0 0.0 0.55 1.0 0.0 0.0 0.0 0.0 1.0 0.0 -1.0 0.0 -1.0 0.0 1.0" name="init_qpos"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="0" condim="3" density="5.0" friction="1.5 0.1 0.1" margin="0.01" rgba="0.8 0.6 0.4 1"/>
|
||||
</default>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 0.75">
|
||||
<geom name="torso_geom" pos="0 0 0" size="0.25" type="sphere"/>
|
||||
<!--joint armature="0" damping="0" limited="false" margin="0.01" name="root" pos="0 0 0" type="free"/-->
|
||||
<body name="front_left_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="aux_1_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body name="aux_1" pos="0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_1" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="left_leg_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body pos="0.2 0.2 0" name="front_left_foot">
|
||||
<joint axis="-1 1 0" name="ankle_1" pos="0.0 0.0 0.0" range="30 100" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 0.4 0.0" name="left_ankle_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="front_right_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="aux_2_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_2" pos="-0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_2" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="right_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 0.2 0" name="front_right_foot">
|
||||
<joint axis="1 1 0" name="ankle_2" pos="0.0 0.0 0.0" range="-100 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 0.4 0.0" name="right_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="aux_3_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_3" pos="-0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_3" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="back_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 -0.2 0" name="left_back_foot">
|
||||
<joint axis="-1 1 0" name="ankle_3" pos="0.0 0.0 0.0" range="-100 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 -0.4 0.0" name="third_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="aux_4_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body name="aux_4" pos="0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_4" pos="0.0 0.0 0.0" range="-40 40" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="rightback_leg_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
<body pos="0.2 -0.2 0" name="right_back_foot">
|
||||
<joint axis="1 1 0" name="ankle_4" pos="0.0 0.0 0.0" range="30 100" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 -0.4 0.0" name="fourth_ankle_geom" size="0.08" type="capsule" rgba=".8 .5 .3 1"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_3" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_3" gear="150"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,5 @@
|
||||
<mujoco model="ground_plane">
|
||||
<worldbody>
|
||||
<geom conaffinity="1" condim="3" name="floor" friction="0.8 0.1 0.1" pos="0 0 0" type="plane"/>
|
||||
</worldbody>
|
||||
</mujoco>
|
||||
88
examples/pybullet/gym/envs/mujoco_assets/half_cheetah.xml
Normal file
88
examples/pybullet/gym/envs/mujoco_assets/half_cheetah.xml
Normal file
@@ -0,0 +1,88 @@
|
||||
<!-- Cheetah Model
|
||||
|
||||
The state space is populated with joints in the order that they are
|
||||
defined in this file. The actuators also operate on joints.
|
||||
|
||||
State-Space (name/joint/parameter):
|
||||
- rootx slider position (m)
|
||||
- rootz slider position (m)
|
||||
- rooty hinge angle (rad)
|
||||
- bthigh hinge angle (rad)
|
||||
- bshin hinge angle (rad)
|
||||
- bfoot hinge angle (rad)
|
||||
- fthigh hinge angle (rad)
|
||||
- fshin hinge angle (rad)
|
||||
- ffoot hinge angle (rad)
|
||||
- rootx slider velocity (m/s)
|
||||
- rootz slider velocity (m/s)
|
||||
- rooty hinge angular velocity (rad/s)
|
||||
- bthigh hinge angular velocity (rad/s)
|
||||
- bshin hinge angular velocity (rad/s)
|
||||
- bfoot hinge angular velocity (rad/s)
|
||||
- fthigh hinge angular velocity (rad/s)
|
||||
- fshin hinge angular velocity (rad/s)
|
||||
- ffoot hinge angular velocity (rad/s)
|
||||
|
||||
Actuators (name/actuator/parameter):
|
||||
- bthigh hinge torque (N m)
|
||||
- bshin hinge torque (N m)
|
||||
- bfoot hinge torque (N m)
|
||||
- fthigh hinge torque (N m)
|
||||
- fshin hinge torque (N m)
|
||||
- ffoot hinge torque (N m)
|
||||
|
||||
-->
|
||||
<mujoco model="cheetah">
|
||||
<compiler angle="radian" coordinate="local" inertiafromgeom="true" settotalmass="14"/>
|
||||
<default>
|
||||
<joint armature=".1" damping=".01" limited="true" solimplimit="0 .8 .03" solreflimit=".02 1" stiffness="8"/>
|
||||
<geom conaffinity="0" condim="3" contype="1" friction="0.8 .1 .1" rgba="0.8 0.6 .4 1" solimp="0.0 0.8 0.01" solref="0.02 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1"/>
|
||||
</default>
|
||||
<size nstack="300000" nuser_geom="1"/>
|
||||
<option gravity="0 0 -9.81" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 .7">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="ignorex" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="ignorez" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="ignorey" pos="0 0 0" stiffness="0" type="hinge"/>
|
||||
<geom fromto="-.5 0 0 .5 0 0" name="torso" size="0.046" type="capsule"/>
|
||||
<geom axisangle="0 1 0 .87" name="head" pos=".6 0 .1" size="0.046 .15" type="capsule"/>
|
||||
<!-- <site name='tip' pos='.15 0 .11'/>-->
|
||||
<body name="bthigh" pos="-.5 0 0">
|
||||
<joint axis="0 1 0" damping="6" name="bthigh" pos="0 0 0" range="-.52 1.05" stiffness="240" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -3.8" name="bthigh" pos=".1 0 -.13" size="0.046 .145" type="capsule"/>
|
||||
<body name="bshin" pos=".16 0 -.25">
|
||||
<joint axis="0 1 0" damping="4.5" name="bshin" pos="0 0 0" range="-.785 .785" stiffness="180" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -2.03" name="bshin" pos="-.14 0 -.07" rgba="0.9 0.6 0.6 1" size="0.046 .15" type="capsule"/>
|
||||
<body name="bfoot" pos="-.28 0 -.14">
|
||||
<joint axis="0 1 0" damping="3" name="bfoot" pos="0 0 0" range="-.4 .785" stiffness="120" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.27" name="bfoot" pos=".03 0 -.097" rgba="0.9 0.6 0.6 1" size="0.046 .094" type="capsule"/>
|
||||
<inertial mass="10"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="fthigh" pos=".5 0 0">
|
||||
<joint axis="0 1 0" damping="4.5" name="fthigh" pos="0 0 0" range="-1.5 0.8" stiffness="180" type="hinge"/>
|
||||
<geom axisangle="0 1 0 .52" name="fthigh" pos="-.07 0 -.12" size="0.046 .133" type="capsule"/>
|
||||
<body name="fshin" pos="-.14 0 -.24">
|
||||
<joint axis="0 1 0" damping="3" name="fshin" pos="0 0 0" range="-1.2 1.1" stiffness="120" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.6" name="fshin" pos=".065 0 -.09" rgba="0.9 0.6 0.6 1" size="0.046 .106" type="capsule"/>
|
||||
<body name="ffoot" pos=".13 0 -.18">
|
||||
<joint axis="0 1 0" damping="1.5" name="ffoot" pos="0 0 0" range="-3.1 -0.3" stiffness="60" type="hinge"/>
|
||||
<geom axisangle="0 1 0 -.6" name="ffoot" pos=".045 0 -.07" rgba="0.9 0.6 0.6 1" size="0.046 .07" type="capsule"/>
|
||||
<inertial mass="10"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor gear="120" joint="bthigh" name="bthigh"/>
|
||||
<motor gear="90" joint="bshin" name="bshin"/>
|
||||
<motor gear="60" joint="bfoot" name="bfoot"/>
|
||||
<motor gear="120" joint="fthigh" name="fthigh"/>
|
||||
<motor gear="60" joint="fshin" name="fshin"/>
|
||||
<motor gear="30" joint="ffoot" name="ffoot"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
39
examples/pybullet/gym/envs/mujoco_assets/hopper.xml
Normal file
39
examples/pybullet/gym/envs/mujoco_assets/hopper.xml
Normal file
@@ -0,0 +1,39 @@
|
||||
<mujoco model="hopper">
|
||||
<compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" friction="0.8 .1 .1" material="geom" rgba="0.8 0.6 .4 1" solimp=".8 .8 .01" solref=".02 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" timestep="0.002"/>
|
||||
<worldbody>
|
||||
<!-- CHANGE: body pos="" deleted for all bodies (you can also set pos="0 0 0", it works)
|
||||
Interpretation of body pos="" depends on coordinate="global" above.
|
||||
Bullet doesn't support global coordinates in bodies, little motivation to fix this, as long as it works without pos="" as well.
|
||||
After this change, Hopper still loads and works in MuJoCo simulator.
|
||||
-->
|
||||
<body name="torso">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="ignore1" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="ignore2" pos="0 0 0" ref="1.25" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="ignore3" pos="0 0 0" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0 0 1.45 0 0 1.05" name="torso_geom" size="0.05" type="capsule"/>
|
||||
<body name="thigh">
|
||||
<joint axis="0 -1 0" name="thigh_joint" pos="0 0 1.05" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 1.05 0 0 0.6" name="thigh_geom" size="0.05" type="capsule"/>
|
||||
<body name="leg">
|
||||
<joint axis="0 -1 0" name="leg_joint" pos="0 0 0.6" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 0.6 0 0 0.1" name="leg_geom" size="0.04" type="capsule"/>
|
||||
<body name="foot">
|
||||
<joint axis="0 -1 0" name="foot_joint" pos="0 0 0.1" range="-45 45" type="hinge"/>
|
||||
<geom fromto="-0.13 0 0.1 0.26 0 0.1" name="foot_geom" size="0.06" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="thigh_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="leg_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="foot_joint"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
107
examples/pybullet/gym/envs/mujoco_assets/humanoid_symmetric.xml
Normal file
107
examples/pybullet/gym/envs/mujoco_assets/humanoid_symmetric.xml
Normal file
@@ -0,0 +1,107 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="3" friction="0.8 0.1 0.1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 1.4">
|
||||
<!--joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="free"/-->
|
||||
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/>
|
||||
<geom name="head" pos="0 0 .19" size=".09" type="sphere" user="258"/>
|
||||
<geom fromto="-.01 -.06 -.12 -.01 .06 -.12" name="uwaist" size="0.06" type="capsule"/>
|
||||
<body name="lwaist" pos="-.01 0 -0.260" quat="1.000 0 -0.002 0">
|
||||
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/>
|
||||
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/>
|
||||
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/>
|
||||
<body name="pelvis" pos="0 0 -0.165" quat="1.000 0 -0.002 0">
|
||||
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/>
|
||||
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/>
|
||||
<body name="right_thigh" pos="0 -0.1 -0.04">
|
||||
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0.01 -.34" name="right_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="right_shin" pos="0 0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="right_shin1" size="0.049" type="capsule"/>
|
||||
<body name="right_foot" pos="0 0 -0.45">
|
||||
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_thigh" pos="0 0.1 -0.04">
|
||||
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 -0.01 -.34" name="left_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="left_shin" pos="0 -0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="left_shin1" size="0.049" type="capsule"/>
|
||||
<body name="left_foot" pos="0 0 -0.45">
|
||||
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_upper_arm" pos="0 -0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="right_lower_arm" pos=".18 -.18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/>
|
||||
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_upper_arm" pos="0 0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="left_lower_arm" pos=".18 .18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/>
|
||||
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,115 @@
|
||||
<mujoco model="humanoid">
|
||||
<compiler angle="degree" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003">
|
||||
<!-- <flags solverstat="enable" energy="enable"/>-->
|
||||
</option>
|
||||
<size nkey="5" nuser_geom="1"/>
|
||||
<visual>
|
||||
<map fogend="5" fogstart="3"/>
|
||||
</visual>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1=".4 .5 .6" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<!-- <texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>-->
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<body name="torso" pos="0 0 1.4">
|
||||
<!--joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="free"/-->
|
||||
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/>
|
||||
<geom name="head" pos="0 0 .19" size=".09" type="sphere" user="258"/>
|
||||
<geom fromto="-.01 -.06 -.12 -.01 .06 -.12" name="uwaist" size="0.06" type="capsule"/>
|
||||
<body name="lwaist" pos="-.01 0 -0.260" quat="1.000 0 -0.002 0">
|
||||
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/>
|
||||
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/>
|
||||
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/>
|
||||
<body name="pelvis" pos="0 0 -0.165" quat="1.000 0 -0.002 0">
|
||||
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/>
|
||||
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/>
|
||||
<body name="right_thigh" pos="0 -0.1 -0.04">
|
||||
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0.01 -.34" name="right_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="right_shin" pos="0 0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="right_shin1" size="0.049" type="capsule"/>
|
||||
<body name="right_foot" pos="0 0 -0.45">
|
||||
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_thigh" pos="0 0.1 -0.04">
|
||||
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/>
|
||||
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 -0.01 -.34" name="left_thigh1" size="0.06" type="capsule"/>
|
||||
<body name="left_shin" pos="0 -0.01 -0.403">
|
||||
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 -.3" name="left_shin1" size="0.049" type="capsule"/>
|
||||
<body name="left_foot" pos="0 0 -0.45">
|
||||
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_upper_arm" pos="0 -0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="right_lower_arm" pos=".18 -.18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/>
|
||||
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
<body name="left_upper_arm" pos="0 0.17 0.06">
|
||||
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/>
|
||||
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/>
|
||||
<body name="left_lower_arm" pos=".18 .18 -.18">
|
||||
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/>
|
||||
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<tendon>
|
||||
<fixed name="left_hipknee">
|
||||
<joint coef="-1" joint="left_hip_y"/>
|
||||
<joint coef="1" joint="left_knee"/>
|
||||
</fixed>
|
||||
<fixed name="right_hipknee">
|
||||
<joint coef="-1" joint="right_hip_y"/>
|
||||
<joint coef="1" joint="right_knee"/>
|
||||
</fixed>
|
||||
</tendon>
|
||||
<actuator><!-- this section is not supported, same constants in code -->
|
||||
<motor gear="100" joint="abdomen_y" name="abdomen_y"/>
|
||||
<motor gear="100" joint="abdomen_z" name="abdomen_z"/>
|
||||
<motor gear="100" joint="abdomen_x" name="abdomen_x"/>
|
||||
<motor gear="100" joint="right_hip_x" name="right_hip_x"/>
|
||||
<motor gear="100" joint="right_hip_z" name="right_hip_z"/>
|
||||
<motor gear="300" joint="right_hip_y" name="right_hip_y"/>
|
||||
<motor gear="200" joint="right_knee" name="right_knee"/>
|
||||
<motor gear="100" joint="left_hip_x" name="left_hip_x"/>
|
||||
<motor gear="100" joint="left_hip_z" name="left_hip_z"/>
|
||||
<motor gear="300" joint="left_hip_y" name="left_hip_y"/>
|
||||
<motor gear="200" joint="left_knee" name="left_knee"/>
|
||||
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/>
|
||||
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/>
|
||||
<motor gear="25" joint="right_elbow" name="right_elbow"/>
|
||||
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/>
|
||||
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/>
|
||||
<motor gear="25" joint="left_elbow" name="left_elbow"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,47 @@
|
||||
<!-- Cartpole Model
|
||||
|
||||
The state space is populated with joints in the order that they are
|
||||
defined in this file. The actuators also operate on joints.
|
||||
|
||||
State-Space (name/joint/parameter):
|
||||
- cart slider position (m)
|
||||
- pole hinge angle (rad)
|
||||
- cart slider velocity (m/s)
|
||||
- pole hinge angular velocity (rad/s)
|
||||
|
||||
Actuators (name/actuator/parameter):
|
||||
- cart motor force x (N)
|
||||
|
||||
-->
|
||||
<mujoco model="cartpole">
|
||||
<compiler coordinate="local" inertiafromgeom="true"/>
|
||||
<custom>
|
||||
<numeric data="2" name="frame_skip"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint damping="0.05"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="1e-5 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<geom name="floor" pos="0 0 -3.0" rgba="0.8 0.9 0.8 1" size="40 40 40" type="plane"/>
|
||||
<geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/>
|
||||
<body name="cart" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" margin="0.01" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<body name="pole2" pos="0 0 0.6">
|
||||
<joint axis="0 1 0" name="hinge2" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole2" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<!--site name="tip" pos="0 0 .6" size="0.01 0.01"/-->
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1" gear="500" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
@@ -0,0 +1,27 @@
|
||||
<mujoco model="inverted pendulum">
|
||||
<compiler inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="0" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
<tendon/>
|
||||
<motor ctrlrange="-3 3"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.02"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<!--geom name="ground" type="plane" pos="0 0 0" /-->
|
||||
<geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/>
|
||||
<body name="cart" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" limited="false" range="-90 90" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.001 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.049 0.3" type="capsule"/>
|
||||
<!-- <body name="pole2" pos="0.001 0 0.6"><joint name="hinge2" type="hinge" pos="0 0 0" axis="0 1 0"/><geom name="cpole2" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05 0.3" rgba="0.7 0 0.7 1"/><site name="tip2" pos="0 0 .6"/></body>-->
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor gear="100" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
91
examples/pybullet/gym/envs/mujoco_assets/pusher.xml
Normal file
91
examples/pybullet/gym/envs/mujoco_assets/pusher.xml
Normal file
@@ -0,0 +1,91 @@
|
||||
<mujoco model="arm3d">
|
||||
<compiler inertiafromgeom="true" angle="radian" coordinate="local"/>
|
||||
<option timestep="0.01" gravity="0 0 0" integrator="RK4" />
|
||||
|
||||
<default>
|
||||
<joint armature='0.04' damping="1" limited="true"/>
|
||||
<geom friction=".8 .1 .1" density="300" margin="0.002" condim="1" contype="0" conaffinity="0"/>
|
||||
</default>
|
||||
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom name="table" type="plane" pos="0 0.5 -0.325" size="1 1 0.1" contype="1" conaffinity="1"/>
|
||||
|
||||
<body name="r_shoulder_pan_link" pos="0 -0.6 0">
|
||||
<geom name="e1" type="sphere" rgba="0.6 0.6 0.6 1" pos="-0.06 0.05 0.2" size="0.05" />
|
||||
<geom name="e2" type="sphere" rgba="0.6 0.6 0.6 1" pos=" 0.06 0.05 0.2" size="0.05" />
|
||||
<geom name="e1p" type="sphere" rgba="0.1 0.1 0.1 1" pos="-0.06 0.09 0.2" size="0.03" />
|
||||
<geom name="e2p" type="sphere" rgba="0.1 0.1 0.1 1" pos=" 0.06 0.09 0.2" size="0.03" />
|
||||
<geom name="sp" type="capsule" fromto="0 0 -0.4 0 0 0.2" size="0.1" />
|
||||
<joint name="r_shoulder_pan_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-2.2854 1.714602" damping="1.0" />
|
||||
|
||||
<body name="r_shoulder_lift_link" pos="0.1 0 0">
|
||||
<geom name="sl" type="capsule" fromto="0 -0.1 0 0 0.1 0" size="0.1" />
|
||||
<joint name="r_shoulder_lift_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 1.3963" damping="1.0" />
|
||||
|
||||
<body name="r_upper_arm_roll_link" pos="0 0 0">
|
||||
<geom name="uar" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="r_upper_arm_roll_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.5 1.7" damping="0.1" />
|
||||
|
||||
<body name="r_upper_arm_link" pos="0 0 0">
|
||||
<geom name="ua" type="capsule" fromto="0 0 0 0.4 0 0" size="0.06" />
|
||||
|
||||
<body name="r_elbow_flex_link" pos="0.4 0 0">
|
||||
<geom name="ef" type="capsule" fromto="0 -0.02 0 0.0 0.02 0" size="0.06" />
|
||||
<joint name="r_elbow_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.3213 0" damping="0.1" />
|
||||
|
||||
<body name="r_forearm_roll_link" pos="0 0 0">
|
||||
<geom name="fr" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="r_forearm_roll_joint" type="hinge" limited="true" pos="0 0 0" axis="1 0 0" damping=".1" range="-1.5 1.5"/>
|
||||
|
||||
<body name="r_forearm_link" pos="0 0 0">
|
||||
<geom name="fa" type="capsule" fromto="0 0 0 0.291 0 0" size="0.05" />
|
||||
|
||||
<body name="r_wrist_flex_link" pos="0.321 0 0">
|
||||
<geom name="wf" type="capsule" fromto="0 -0.02 0 0 0.02 0" size="0.01" />
|
||||
<joint name="r_wrist_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.094 0" damping=".1" />
|
||||
|
||||
<body name="r_wrist_roll_link" pos="0 0 0">
|
||||
<joint name="r_wrist_roll_joint" type="hinge" pos="0 0 0" limited="true" axis="1 0 0" damping="0.1" range="-1.5 1.5"/>
|
||||
<body name="fingertip" pos="0 0 0">
|
||||
<geom name="tip_arml" type="sphere" pos="0.1 -0.1 0." size="0.01" />
|
||||
<geom name="tip_armr" type="sphere" pos="0.1 0.1 0." size="0.01" />
|
||||
</body>
|
||||
<geom type="capsule" fromto="0 -0.1 0. 0.0 +0.1 0" size="0.02" contype="1" conaffinity="1" />
|
||||
<geom type="capsule" fromto="0 -0.1 0. 0.1 -0.1 0" size="0.02" contype="1" conaffinity="1" />
|
||||
<geom type="capsule" fromto="0 +0.1 0. 0.1 +0.1 0." size="0.02" contype="1" conaffinity="1" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
||||
<!--<body name="object" pos="0.55 -0.3 -0.275" >-->
|
||||
<body name="object" pos="0.45 -0.05 -0.275" >
|
||||
<geom rgba="1 1 1 0" type="sphere" size="0.05 0.05 0.05" density="0.00001" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="cylinder" size="0.05 0.05 0.05" density="0.00001" contype="1" conaffinity="0"/>
|
||||
<joint name="obj_slidey" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
<joint name="obj_slidex" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
</body>
|
||||
|
||||
<body name="goal" pos="0.45 -0.05 -0.3230">
|
||||
<geom rgba="1 0 0 1" type="cylinder" size="0.08 0.001 0.1" density='0.00001' contype="0" conaffinity="0"/>
|
||||
<joint name="goal_slidey" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
<joint name="goal_slidex" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor joint="r_shoulder_pan_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_shoulder_lift_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_upper_arm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_elbow_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_forearm_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_flex_joint" ctrlrange="-2.0 2.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_roll_joint" ctrlrange="-2.0 2.0" ctrllimited="true"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
39
examples/pybullet/gym/envs/mujoco_assets/reacher.xml
Normal file
39
examples/pybullet/gym/envs/mujoco_assets/reacher.xml
Normal file
@@ -0,0 +1,39 @@
|
||||
<mujoco model="reacher">
|
||||
<compiler angle="radian" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<!-- Arena -->
|
||||
<geom conaffinity="0" contype="0" name="ground" pos="0 0 0" rgba="0.9 0.9 0.9 1" size="1 1 10" type="plane"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 .3 -.3 .01" name="sideS" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto=" .3 -.3 .01 .3 .3 .01" name="sideE" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 .3 .01 .3 .3 .01" name="sideN" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 -.3 .3 .01" name="sideW" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<!-- Arm -->
|
||||
<geom conaffinity="0" contype="0" fromto="0 0 0 0 0 0.02" name="root" rgba="0.9 0.4 0.6 1" size=".011" type="cylinder"/>
|
||||
<body name="body0" pos="0 0 .01">
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link0" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="false" name="joint0" pos="0 0 0" type="hinge"/>
|
||||
<body name="body1" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="true" name="joint1" pos="0 0 0" range="-3.0 3.0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link1" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="fingertip" pos="0.11 0 0">
|
||||
<geom contype="0" name="fingertip" pos="0 0 0" rgba="0.0 0.8 0.6 1" size=".01" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<!-- Target -->
|
||||
<body name="target" pos="0 0 .01">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="true" name="target_x" pos="0 0 0" range="-.27 .27" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="true" name="target_y" pos="0 0 0" range="-.27 .27" stiffness="0" type="slide"/>
|
||||
<geom conaffinity="0" contype="0" name="target" pos="0 0 0" rgba="0.9 0.2 0.2 1" size=".009" type="sphere"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint0"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint1"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
101
examples/pybullet/gym/envs/mujoco_assets/striker.xml
Normal file
101
examples/pybullet/gym/envs/mujoco_assets/striker.xml
Normal file
@@ -0,0 +1,101 @@
|
||||
<mujoco model="arm3d">
|
||||
<compiler inertiafromgeom="true" angle="radian" coordinate="local"/>
|
||||
<option timestep="0.01" gravity="0 0 0" integrator="RK4"/>
|
||||
|
||||
<default>
|
||||
<joint armature='0.04' damping="1" limited="true"/>
|
||||
<geom friction=".0 .0 .0" density="300" margin="0.002" condim="1" contype="0" conaffinity="0"/>
|
||||
</default>
|
||||
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom name="table" type="plane" pos="0 0.5 -0.325" size="1 1 0.1" contype="1" conaffinity="1"/>
|
||||
|
||||
<body name="r_shoulder_pan_link" pos="0 -0.6 0">
|
||||
<geom name="e1" type="sphere" rgba="0.6 0.6 0.6 1" pos="-0.06 0.05 0.2" size="0.05"/>
|
||||
<geom name="e2" type="sphere" rgba="0.6 0.6 0.6 1" pos=" 0.06 0.05 0.2" size="0.05"/>
|
||||
<geom name="e1p" type="sphere" rgba="0.1 0.1 0.1 1" pos="-0.06 0.09 0.2" size="0.03"/>
|
||||
<geom name="e2p" type="sphere" rgba="0.1 0.1 0.1 1" pos=" 0.06 0.09 0.2" size="0.03"/>
|
||||
<geom name="sp" type="capsule" fromto="0 0 -0.4 0 0 0.2" size="0.1" />
|
||||
<joint name="r_shoulder_pan_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-2.2854 1.714602" damping="1.0" />
|
||||
|
||||
<body name="r_shoulder_lift_link" pos="0.1 0 0">
|
||||
<geom name="sl" type="capsule" fromto="0 -0.1 0 0 0.1 0" size="0.1" />
|
||||
<joint name="r_shoulder_lift_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 1.3963" damping="1.0" />
|
||||
|
||||
<body name="r_upper_arm_roll_link" pos="0 0 0">
|
||||
<geom name="uar" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="r_upper_arm_roll_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.5 1.7" damping="0.1" />
|
||||
|
||||
<body name="r_upper_arm_link" pos="0 0 0">
|
||||
<geom name="ua" type="capsule" fromto="0 0 0 0.4 0 0" size="0.06" />
|
||||
|
||||
<body name="r_elbow_flex_link" pos="0.4 0 0">
|
||||
<geom name="ef" type="capsule" fromto="0 -0.02 0 0.0 0.02 0" size="0.06" />
|
||||
<joint name="r_elbow_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.3213 0" damping="0.1" />
|
||||
|
||||
<body name="r_forearm_roll_link" pos="0 0 0">
|
||||
<geom name="fr" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" />
|
||||
<joint name="r_forearm_roll_joint" type="hinge" limited="true" pos="0 0 0" axis="1 0 0" damping=".1" range="-1.5 1.5"/>
|
||||
|
||||
<body name="r_forearm_link" pos="0 0 0">
|
||||
<geom name="fa" type="capsule" fromto="0 0 0 0.291 0 0" size="0.05" />
|
||||
|
||||
<body name="r_wrist_flex_link" pos="0.321 0 0">
|
||||
<geom name="wf" type="capsule" fromto="0 -0.02 0 0 0.02 0" size="0.01" />
|
||||
<joint name="r_wrist_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.094 0" damping=".1" />
|
||||
|
||||
<body name="r_wrist_roll_link" pos="0 0 0">
|
||||
<joint name="r_wrist_roll_joint" type="hinge" pos="0 0 0" limited="true" axis="1 0 0" damping="0.1" range="-1.5 1.5"/>
|
||||
|
||||
|
||||
<body name="fingertip" pos="0 0 0">
|
||||
<geom conaffinity="1" contype="1" name="tip_arml" pos="0.017 0 0" size="0.003 0.12 0.05" type="box" />
|
||||
|
||||
</body>
|
||||
<geom conaffinity="1" contype="1" fromto="0 -0.1 0. 0.0 +0.1 0" size="0.02" type="capsule" />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
||||
<body name="object" pos="0 0 -0.270" >
|
||||
<geom type="sphere" rgba="1 1 1 1" pos="0 0 0" size="0.05 0.05 0.05" contype="1" conaffinity="0"/>
|
||||
<joint name="obj_slidey" armature="0.1" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
<joint name="obj_slidex" armature="0.1" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="0.5"/>
|
||||
</body>
|
||||
|
||||
<body name="goal" pos="0.0 0.0 -0.3230">
|
||||
<geom rgba="1. 1. 1. 0" pos="0 0 0" type="box" size="0.01 0.01 0.01" contype="0" conaffinity="0"/>
|
||||
<body pos="0 0 0">
|
||||
<geom rgba="1. 1. 1. 1" pos="0 0.075 0.04" type="box" size="0.032 0.001 0.04" contype="0" conaffinity="1"/>
|
||||
</body>
|
||||
<body name="coaster" pos="0 0 0">
|
||||
<geom rgba="1. 1. 1. 1" type="cylinder" size="0.08 0.001 0.1" density='1000000' contype="0" conaffinity="0"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 0.785">
|
||||
<geom rgba="1. 1. 1. 1" pos="0 0.075 0.04" type="box" size="0.032 0.001 0.04" contype="0" conaffinity="1"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 -0.785">
|
||||
<geom rgba="1. 1. 1. 1" pos="0 0.075 0.04" type="box" size="0.032 0.001 0.04" contype="0" conaffinity="1"/>
|
||||
</body>
|
||||
<joint name="goal_free" type="free" pos="0 0 0" limited="false" damping="0"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor joint="r_shoulder_pan_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_shoulder_lift_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_upper_arm_roll_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_elbow_flex_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_forearm_roll_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_flex_joint" ctrlrange="-3.0 3.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_roll_joint" ctrlrange="-3.0 3.0" ctrllimited="true"/>
|
||||
</actuator>
|
||||
|
||||
</mujoco>
|
||||
127
examples/pybullet/gym/envs/mujoco_assets/thrower.xml
Normal file
127
examples/pybullet/gym/envs/mujoco_assets/thrower.xml
Normal file
@@ -0,0 +1,127 @@
|
||||
<mujoco model="arm3d">
|
||||
<compiler inertiafromgeom="true" angle="radian" coordinate="local"/>
|
||||
<option timestep="0.01" gravity="0 0 -9.81" integrator="RK4"/>
|
||||
<default>
|
||||
<joint armature='0.75' damping="1" limited="true"/>
|
||||
<geom friction=".8 .1 .1" density="300" margin="0.002" condim="1" contype="0" conaffinity="0"/>
|
||||
</default>
|
||||
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
|
||||
<geom type="plane" pos="0 0.5 -0.325" size="1 1 0.1" contype="1" conaffinity="1"/>
|
||||
|
||||
<body name="r_shoulder_pan_link" pos="0 -0.6 0">
|
||||
<geom name="e1" type="sphere" rgba="0.6 0.6 0.6 1" pos="-0.06 0.05 0.2" size="0.05" density="0.0001"/>
|
||||
<geom name="e2" type="sphere" rgba="0.6 0.6 0.6 1" pos=" 0.06 0.05 0.2" size="0.05" density="0.0001"/>
|
||||
<geom name="e1p" type="sphere" rgba="0.1 0.1 0.1 1" pos="-0.06 0.09 0.2" size="0.03" density="0.0001"/>
|
||||
<geom name="e2p" type="sphere" rgba="0.1 0.1 0.1 1" pos=" 0.06 0.09 0.2" size="0.03" density="0.0001"/>
|
||||
<geom name="sp" type="capsule" fromto="0 0 -0.4 0 0 0.2" size="0.1" density="1"/>
|
||||
<joint name="r_shoulder_pan_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-0.4854 1.214602" damping="1.0"/>
|
||||
|
||||
<body name="r_shoulder_lift_link" pos="0.1 0 0">
|
||||
<geom name="sl" type="capsule" fromto="0 -0.1 0 0 0.1 0" size="0.1" density="0.0001"/>
|
||||
<joint name="r_shoulder_lift_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 0.7963" damping="1.0"/>
|
||||
|
||||
<body name="r_upper_arm_roll_link" pos="0 0 0">
|
||||
<geom name="uar" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" density="0.0001"/>
|
||||
<joint name="r_upper_arm_roll_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.5 1.7" damping="1.0"/>
|
||||
|
||||
<body name="r_upper_arm_link" pos="0 0 0">
|
||||
<geom name="ua" type="capsule" fromto="0 0 0 0.4 0 0" size="0.06" density="0.0001"/>
|
||||
|
||||
<body name="r_elbow_flex_link" pos="0.4 0 0">
|
||||
<geom name="ef" type="capsule" fromto="0 -0.02 0 0.0 0.02 0" size="0.06" density="0.0001"/>
|
||||
<joint name="r_elbow_flex_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.7 0.7" damping="1.0"/>
|
||||
|
||||
<body name="r_forearm_roll_link" pos="0 0 0">
|
||||
<geom name="fr" type="capsule" fromto="-0.1 0 0 0.1 0 0" size="0.02" density="0.0001"/>
|
||||
<joint name="r_forearm_roll_joint" type="hinge" limited="true" pos="0 0 0" axis="1 0 0" damping="1.0" range="-1.5 1.5"/>
|
||||
|
||||
<body name="r_forearm_link" pos="0 0 0" axisangle="1 0 0 0.392">
|
||||
<geom name="fa" type="capsule" fromto="0 0 0 0 0 0.291" size="0.05" density="0.0001"/>
|
||||
|
||||
<body name="r_wrist_flex_link" pos="0 0 0.321" axisangle="0 0 1 1.57">
|
||||
<geom name="wf" type="capsule" fromto="0 -0.02 0 0 0.02 0" size="0.01" density="0.0001"/>
|
||||
<joint name="r_wrist_flex_joint" type="hinge" pos="0 0 0" axis="0 0 1" range="-1.0 1.0" damping="1.0" />
|
||||
|
||||
<body name="r_wrist_roll_link" pos="0 0 0" axisangle="0 1 0 -1.178">
|
||||
<joint name="r_wrist_roll_joint" type="hinge" pos="0 0 0" limited="true" axis="0 1 0" damping="1.0" range="0 2.25"/>
|
||||
<geom type="capsule" fromto="0 -0.05 0 0 0.05 0" size="0.01" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<body name="fingertip" pos="0 0 0" axisangle="0 0 1 0.392">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density=".0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 1.57">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 1.178">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 0.785">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 1.96">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 2.355">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
<body pos="0 0 0" axisangle="0 0 1 2.74">
|
||||
<geom type="capsule" fromto="0 0.025 0 0 0.075 0.075" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.075 0 0.075 0.15" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
<geom type="capsule" fromto="0 0.075 0.15 0 0 0.225" size="0.005" contype="1" conaffinity="1" density="0.0001"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
|
||||
<body name="goal" pos="0.575 0.5 -0.328">
|
||||
<geom rgba="1 1 1 1" type="box" pos="0 0 0.005" size="0.075 0.075 0.001" contype="1" conaffinity="1" density="1000"/>
|
||||
<geom rgba="1 1 1 1" type="box" pos="0.0 0.075 0.034" size="0.075 0.001 0.03" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="box" pos="0.0 -0.075 0.034" size="0.075 0.001 0.03" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="box" pos="0.075 0 0.034" size="0.001 0.075 0.03" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="box" pos="-0.076 0 0.034" size="0.001 0.075 0.03" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="capsule" fromto="0.073 0.073 0.0075 0.073 0.073 0.06" size="0.005" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="capsule" fromto="0.073 -0.073 0.0075 0.073 -0.073 0.06" size="0.005" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="capsule" fromto="-0.073 0.073 0.0075 -0.073 0.073 0.06" size="0.005" contype="1" conaffinity="0"/>
|
||||
<geom rgba="1 1 1 1" type="capsule" fromto="-0.073 -0.073 0.0075 -0.073 -0.073 0.06" size="0.005" contype="1" conaffinity="0"/>
|
||||
<joint name="goal_slidey" type="slide" pos="0 0 0" axis="0 1 0" range="-10.3213 10.3" damping="1.0"/>
|
||||
<joint name="goal_slidex" type="slide" pos="0 0 0" axis="1 0 0" range="-10.3213 10.3" damping="1.0"/>
|
||||
</body>
|
||||
|
||||
<body name="ball" pos="0.5 -0.8 0.275">
|
||||
<geom rgba="1. 1. 1. 1" type="sphere" size="0.03 0.03 0.1" density='25' contype="1" conaffinity="1"/>
|
||||
<joint name="ball_free" type="free" armature='0' damping="0" limited="false"/>
|
||||
</body>
|
||||
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor joint="r_shoulder_pan_joint" ctrlrange="-10.0 10.0" ctrllimited="true" />
|
||||
<motor joint="r_shoulder_lift_joint" ctrlrange="-10.0 10.0" ctrllimited="true" />
|
||||
<motor joint="r_upper_arm_roll_joint" ctrlrange="-10.0 10.0" ctrllimited="true" />
|
||||
<motor joint="r_elbow_flex_joint" ctrlrange="-10.0 10.0" ctrllimited="true" />
|
||||
<motor joint="r_forearm_roll_joint" ctrlrange="-15.0 15.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_flex_joint" ctrlrange="-15.0 15.0" ctrllimited="true" />
|
||||
<motor joint="r_wrist_roll_joint" ctrlrange="-15.0 15.0" ctrllimited="true"/>
|
||||
</actuator>
|
||||
|
||||
</mujoco>
|
||||
52
examples/pybullet/gym/envs/mujoco_assets/walker2d.xml
Normal file
52
examples/pybullet/gym/envs/mujoco_assets/walker2d.xml
Normal file
@@ -0,0 +1,52 @@
|
||||
<mujoco model="walker2d">
|
||||
<compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="0.01" damping=".1" limited="true"/>
|
||||
<geom conaffinity="0" condim="3" contype="1" density="1000" friction="0.8 .1 .1" rgba="0.8 0.6 .4 1"/>
|
||||
</default>
|
||||
<option integrator="RK4" timestep="0.002"/>
|
||||
<worldbody>
|
||||
<!-- CHANGES: see hopper.xml -->
|
||||
<body name="torso">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="ignorex" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="ignorez" pos="0 0 0" ref="1.25" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="ignorey" pos="0 0 0" stiffness="0" type="hinge"/>
|
||||
<geom fromto="0 0 1.45 0 0 1.05" name="torso_geom" size="0.05" type="capsule"/>
|
||||
<body name="thigh">
|
||||
<joint axis="0 -1 0" name="thigh_joint" pos="0 0 1.05" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 1.05 0 0 0.6" name="thigh_geom" size="0.05" type="capsule"/>
|
||||
<body name="leg">
|
||||
<joint axis="0 -1 0" name="leg_joint" pos="0 0 0.6" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 0.6 0 0 0.1" name="leg_geom" size="0.04" type="capsule"/>
|
||||
<body name="foot">
|
||||
<joint axis="0 -1 0" name="foot_joint" pos="0 0 0.1" range="-45 45" type="hinge"/>
|
||||
<geom fromto="-0.0 0 0.1 0.2 0 0.1" name="foot_geom" size="0.06" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<!-- copied and then replace thigh->thigh_left, leg->leg_left, foot->foot_right -->
|
||||
<body name="thigh_left">
|
||||
<joint axis="0 -1 0" name="thigh_left_joint" pos="0 0 1.05" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 1.05 0 0 0.6" name="thigh_left_geom" rgba=".7 .3 .6 1" size="0.05" type="capsule"/>
|
||||
<body name="leg_left">
|
||||
<joint axis="0 -1 0" name="leg_left_joint" pos="0 0 0.6" range="-150 0" type="hinge"/>
|
||||
<geom fromto="0 0 0.6 0 0 0.1" name="leg_left_geom" rgba=".7 .3 .6 1" size="0.04" type="capsule"/>
|
||||
<body name="foot_left">
|
||||
<joint axis="0 -1 0" name="foot_left_joint" pos="0 0 0.1" range="-45 45" type="hinge"/>
|
||||
<geom fromto="-0.0 0 0.1 0.2 0 0.1" name="foot_left_geom" rgba=".7 .3 .6 1" size="0.06" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<!-- <motor joint="torso_joint" ctrlrange="-100.0 100.0" isctrllimited="true"/>-->
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="thigh_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="leg_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="foot_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="thigh_left_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="leg_left_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="100" joint="foot_left_joint"/>
|
||||
<!-- <motor joint="finger2_rot" ctrlrange="-20.0 20.0" isctrllimited="true"/>-->
|
||||
</actuator>
|
||||
</mujoco>
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,16 @@
|
||||
newmtl stadium_white
|
||||
Ns 96.078431
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 1.000000 1.000000 1.000000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
|
||||
newmtl stadium_grass
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.000000 0.500000 0.000000
|
||||
Ks 0.000000 0.000000 0.000000
|
||||
map_Kd stadium_grass.jpg
|
||||
|
||||
newmtl stadium_dirt
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.600000 0.400000 0.000000
|
||||
Ks 0.000000 0.000000 0.000000
|
||||
File diff suppressed because it is too large
Load Diff
Binary file not shown.
|
After Width: | Height: | Size: 1.0 MiB |
107
examples/pybullet/gym/envs/other_assets/stadium.sdf
Normal file
107
examples/pybullet/gym/envs/other_assets/stadium.sdf
Normal file
@@ -0,0 +1,107 @@
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<gravity>0 0 -9.8</gravity>
|
||||
<model name='roboschool/models_outdoor/stadium/part0.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d0'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part0.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>1.00000 1.00000 1.000000 1</diffuse>
|
||||
<specular>0.1 .1 .1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<model name='roboschool/models_outdoor/stadium/part1.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d1'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='collision_1'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part1.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>0.600000 0.400000 0.000000 1</diffuse>
|
||||
<specular>.5 .5 .5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<model name='part2.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d2'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part2.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.000000 0.500000 0.000000 1</diffuse>
|
||||
<specular>0.4 0.4 0.4 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
84
examples/pybullet/gym/envs/scene_abstract.py
Normal file
84
examples/pybullet/gym/envs/scene_abstract.py
Normal file
@@ -0,0 +1,84 @@
|
||||
# This is the only place cpp_household really imported. From other places, it is referenced as scene_abstract.cpp_household
|
||||
# If this doesn't work, the checklist is:
|
||||
# 1) Build local Bullet physics library (instructions in README)
|
||||
# 2) ldd cpp_household.so
|
||||
# 3) In case of python 2.7 when using pip2 install without -e, the C++ module gets built in python2.7/site-packages,
|
||||
# but when you have roboschool directory in cwd or in parent(s) of cwd, python2 will use that and fail to reach site-packages.
|
||||
# No such behavior in Python3. For example, no zoo scripts will work if you install without -e and run them from
|
||||
# source tree. If you copy zoo script elsewhere, it will work. (upgrade to Python3 if you can.)
|
||||
import sys, os
|
||||
sys.path.append(os.path.dirname(__file__))
|
||||
import pybullet as p
|
||||
|
||||
import gym
|
||||
|
||||
|
||||
class Scene:
|
||||
"A base class for single- and multiplayer scenes"
|
||||
|
||||
def __init__(self, gravity, timestep, frame_skip):
|
||||
self.np_random, seed = gym.utils.seeding.np_random(None)
|
||||
self.timestep = timestep
|
||||
self.frame_skip = frame_skip
|
||||
self.dt = self.timestep * self.frame_skip
|
||||
self.cpp_world = World(gravity, timestep)
|
||||
#self.cpp_world.set_glsl_path(os.path.join(os.path.dirname(__file__), "cpp-household/glsl"))
|
||||
|
||||
#self.big_caption = self.cpp_world.test_window_big_caption # that's a function you can call
|
||||
#self.console_print = self.cpp_world.test_window_print # this too
|
||||
|
||||
self.test_window_still_open = True # or never opened
|
||||
self.human_render_detected = False # if user wants render("human"), we open test window
|
||||
|
||||
self.multiplayer_robots = {}
|
||||
|
||||
def test_window(self):
|
||||
"Call this function every frame, to see what's going on. Not necessary in learning."
|
||||
self.human_render_detected = True
|
||||
return self.test_window_still_open
|
||||
|
||||
def actor_introduce(self, robot):
|
||||
"Usually after scene reset"
|
||||
if not self.multiplayer: return
|
||||
self.multiplayer_robots[robot.player_n] = robot
|
||||
|
||||
def actor_is_active(self, robot):
|
||||
"""
|
||||
Used by robots to see if they are free to exclusiveley put their HUD on the test window.
|
||||
Later can be used for click-focus robots.
|
||||
"""
|
||||
return not self.multiplayer
|
||||
|
||||
def episode_restart(self):
|
||||
"This function gets overridden by specific scene, to reset specific objects into their start positions"
|
||||
self.cpp_world.clean_everything()
|
||||
#self.cpp_world.test_window_history_reset()
|
||||
|
||||
def global_step(self):
|
||||
"""
|
||||
The idea is: apply motor torques for all robots, then call global_step(), then collect
|
||||
observations from robots using step() with the same action.
|
||||
"""
|
||||
#if self.human_render_detected:
|
||||
# self.test_window_still_open = self.cpp_world.test_window()
|
||||
self.cpp_world.step(self.frame_skip)
|
||||
|
||||
class SingleRobotEmptyScene(Scene):
|
||||
multiplayer = False # this class is used "as is" for InvertedPendulum, Reacher
|
||||
|
||||
class World:
|
||||
|
||||
def __init__(self, gravity, timestep):
|
||||
self.gravity = gravity
|
||||
self.timestep = timestep
|
||||
self.clean_everything()
|
||||
|
||||
def clean_everything(self):
|
||||
p.resetSimulation()
|
||||
p.setGravity(0, 0, -self.gravity)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=self.timestep, numSolverIterations=5, numSubSteps=2)
|
||||
|
||||
def step(self, frame_skip):
|
||||
p.stepSimulation()
|
||||
|
||||
|
||||
28
examples/pybullet/gym/envs/scene_stadium.py
Normal file
28
examples/pybullet/gym/envs/scene_stadium.py
Normal file
@@ -0,0 +1,28 @@
|
||||
import os
|
||||
from .scene_abstract import Scene
|
||||
import pybullet as p
|
||||
|
||||
class StadiumScene(Scene):
|
||||
zero_at_running_strip_start_line = True # if False, center of coordinates (0,0,0) will be at the middle of the stadium
|
||||
stadium_halflen = 105*0.25 # FOOBALL_FIELD_HALFLEN
|
||||
stadium_halfwidth = 50*0.25 # FOOBALL_FIELD_HALFWID
|
||||
|
||||
def episode_restart(self):
|
||||
Scene.episode_restart(self) # contains cpp_world.clean_everything()
|
||||
# stadium_pose = cpp_household.Pose()
|
||||
# if self.zero_at_running_strip_start_line:
|
||||
# stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
|
||||
self.stadium = p.loadSDF(os.path.join(os.path.dirname(__file__), "other_assets", "stadium.sdf"))
|
||||
self.ground_plane_mjcf = p.loadMJCF(os.path.join(os.path.dirname(__file__), "mujoco_assets", "ground_plane.xml"))
|
||||
|
||||
class SinglePlayerStadiumScene(StadiumScene):
|
||||
"This scene created by environment, to work in a way as if there was no concept of scene visible to user."
|
||||
multiplayer = False
|
||||
|
||||
class MultiplayerStadiumScene(StadiumScene):
|
||||
multiplayer = True
|
||||
players_count = 3
|
||||
def actor_introduce(self, robot):
|
||||
StadiumScene.actor_introduce(self, robot)
|
||||
i = robot.player_n - 1 # 0 1 2 => -1 0 +1
|
||||
robot.move_robot(0, i, 0)
|
||||
Reference in New Issue
Block a user