File size: 7,648 Bytes
620dc33 |
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 |
import gymnasium as gym
import mujoco
import numpy as np
from gymnasium.spaces import Box
from pathlib import Path
import mujoco.viewer
class StackingEnv(gym.Env):
def __init__(self, render_mode="human"):
super().__init__()
self.render_mode = render_mode
# Load stacking.xml
xml_path = str(Path(__file__).parent.parent / "assets/stacking.xml")
print(f"Loading XML from: {xml_path}")
try:
self.model = mujoco.MjModel.from_xml_path(xml_path)
self.data = mujoco.MjData(self.model)
# Debug: Print model dimensions
self.nq = self.model.nq # Total degrees of freedom
self.nv = self.model.nv # Velocity dimensions
self.nu = self.model.nu # Control dimensions
print(f"Model dimensions - nq: {self.nq}, nv: {self.nv}, nu: {self.nu}")
# Set a valid initial qpos to avoid invalid defaults
self.data.qpos = np.zeros(self.nq)
if self.nq >= 3: # Base position
self.data.qpos[0:3] = [0, 0, 0.1] # x, y, z
if self.nq >= 7: # Orientation
self.data.qpos[3:7] = [1, 0, 0, 0] # quaternion
mujoco.mj_forward(self.model, self.data)
except ValueError as e:
print(f"Error loading model: {e}")
print("Check stacking.xml for valid qpos or keyframe definitions.")
raise
self.viewer = None
if render_mode == "human":
try:
self.viewer = mujoco.viewer.launch_passive(self.model, self.data)
print("Viewer initialized successfully")
except Exception as e:
print(f"Viewer initialization failed: {e}")
# Define observation and action spaces to match dataset
self.observation_space = Box(low=-np.inf, high=np.inf, shape=(21,), dtype=np.float32) # Fixed to (21,) per dataset
self.action_space = Box(low=-1.0, high=1.0, shape=(9,), dtype=np.float32) # Fixed to (9,) per dataset
# Get body IDs and verify they exist
self.block_ids = []
for i in range(3):
block_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_BODY, f"block{i}")
self.block_ids.append(block_id if block_id != -1 else None)
print(f"Block IDs found: {[bid for bid in self.block_ids if bid is not None]}")
self.target_zone_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_BODY, "target_zone")
print(f"Target zone ID: {self.target_zone_id if self.target_zone_id != -1 else 'Not found'}")
# Joint indices (adjusted for dynamic DOFs)
self.joint_ids = list(range(7, min(16, self.nq))) # Limit to 9 joints max to align with obs
self.finger_joint_ids = [14, 15] if self.nq >= 16 and 14 < self.nu and 15 < self.nu else []
def reset(self, seed=None):
super().reset(seed=seed)
nq = self.model.nq
nv = self.model.nv
# Reset to a valid state
self.data.qpos = np.zeros(nq)
self.data.qvel = np.zeros(nv)
if nq >= 3:
self.data.qpos[0:3] = [0, 0, 0.1] # x, y, z
if nq >= 7:
self.data.qpos[3:7] = [1, 0, 0, 0] # quaternion
if nq > 7:
self.data.qpos[7:16] = np.zeros(9) # Limit to 9 joints for obs alignment
# Set block positions
block_positions = [
[0.2, 0.0, 0.025],
[0.25, 0.0, 0.025],
[0.3, 0.0, 0.025]
]
for i, block_id in enumerate(self.block_ids):
if block_id is not None:
self.data.body(block_id).xpos = np.array(block_positions[i])
self.data.qvel[:] = 0.0
mujoco.mj_forward(self.model, self.data)
return self._get_obs(), {}
def step(self, action):
# Clip action to match nu and ensure finite bounds
ctrl_size = min(len(action), self.nu)
clipped_action = np.clip(action[:ctrl_size], -1.0, 1.0)
self.data.ctrl[:ctrl_size] = clipped_action
# Restrict actuator 2 (index 1) to -90° to +90° (-1.57 to 1.57 radians)
if 1 < self.nu:
self.data.ctrl[1] = np.clip(action[1], -1.57, 1.57)
# Handle finger joints if within nu
if len(action) >= 9 and self.finger_joint_ids and all(fid < self.nu for fid in self.finger_joint_ids):
self.data.ctrl[self.finger_joint_ids[0]] = np.clip(action[7], -1.0, 1.0)
self.data.ctrl[self.finger_joint_ids[1]] = np.clip(action[8], -1.0, 1.0)
mujoco.mj_step(self.model, self.data)
reward = -0.01 if not self._is_stacked() else 10.0
terminated = self._is_stacked()
truncated = False
obs = self._get_obs()
info = {"success": terminated}
if self.render_mode == "human" and self.viewer:
self.viewer.sync()
return obs, reward, terminated, truncated, info
def _get_obs(self):
block_pos = [self.data.body(bid).xpos[:3] if bid is not None else np.zeros(3) for bid in self.block_ids]
target_pos = self.data.body(self.target_zone_id).xpos[:3] if self.target_zone_id != -1 else np.zeros(3)
joint_pos = self.data.qpos[7:16] if self.nq > 7 else np.zeros(9) # Limit to 9 joints
obs = np.concatenate([pos for pos in block_pos] + [target_pos] + [joint_pos])
return obs.astype(np.float32)
def _is_stacked(self):
if not any(bid is not None for bid in self.block_ids) or self.target_zone_id == -1:
return False
block_positions = [self.data.body(bid).xpos for bid in self.block_ids if bid is not None]
target_pos = self.data.body(self.target_zone_id).xpos
return all(np.linalg.norm(b[:2] - target_pos[:2]) < 0.05 for b in block_positions)
def close(self):
if self.viewer:
self.viewer.close()
if __name__ == "__main__":
import argparse
import time
parser = argparse.ArgumentParser()
parser.add_argument("--render_mode", default="human")
parser.add_argument("--fps", type=int, default=15, help="Frames per second")
args = parser.parse_args()
try:
env = StackingEnv(render_mode=args.render_mode)
obs, _ = env.reset()
print("Initial observation shape:", obs.shape)
print("Environment initialized successfully!")
if args.render_mode == "human":
print("Simulation started at", args.fps, "FPS. Use viewer 'Joint' or 'Control' tabs to adjust joints, with actuator 2 limited to 180-degree range (-90° to +90°).")
print("Press Ctrl+C to exit.")
step_delay = 1.0 / args.fps
try:
while env.viewer and env.viewer.is_running():
mujoco.mj_step(env.model, env.data)
if env.render_mode == "human" and env.viewer:
env.viewer.sync()
time.sleep(step_delay)
except KeyboardInterrupt:
print("Stopped by user")
else:
print("Environment test completed successfully!")
except Exception as e:
print(f"Error: {e}")
print("\nTo debug this issue:")
print("1. Check stacking.xml for valid qpos or keyframe definitions")
print("2. Ensure qpos has exactly {env.model.nq} values")
print("3. Verify the joint structure in both XML files matches the code assumptions")
finally:
try:
env.close()
except:
pass |