Skip to content

Commit

Permalink
Merge pull request #6 from Zeroth-Robotics/revert-3-sim2sim
Browse files Browse the repository at this point in the history
Revert "sim2sim"
  • Loading branch information
jingxiangmo authored Oct 4, 2024
2 parents 70067e9 + c9c97fb commit 972a2ee
Show file tree
Hide file tree
Showing 10 changed files with 68 additions and 346 deletions.
4 changes: 2 additions & 2 deletions sim/algo/ppo/on_policy_runner.py
Original file line number Diff line number Diff line change
Expand Up @@ -92,11 +92,11 @@ def __init__(self, env: VecEnv, train_cfg: dict, log_dir: Optional[str] = None,

_, _ = self.env.reset()

def learn(self, name: str, num_learning_iterations: int, init_at_random_ep_len: bool = False) -> None:
def learn(self, num_learning_iterations: int, init_at_random_ep_len: bool = False) -> None:
# initialize writer
if self.log_dir is not None and self.writer is None:
wandb.init(
project=name.split('_')[0],
project="XBot",
sync_tensorboard=True,
name=self.wandb_run_name,
config=self.all_cfg,
Expand Down
20 changes: 2 additions & 18 deletions sim/envs/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
from sim.envs.humanoids.g1_env import G1FreeEnv
from sim.envs.humanoids.h1_config import H1Cfg, H1CfgPPO
from sim.envs.humanoids.h1_env import H1FreeEnv
from sim.envs.humanoids.stompymicro_config import StompyMicroCfg, StompyMicroStandingCfg, StompyMicroWalkingCfg, StompyMicroCfgPPO
from sim.envs.humanoids.stompymicro_config import StompyMicroCfg, StompyMicroCfgPPO
from sim.envs.humanoids.stompymicro_env import StompyMicroEnv
from sim.envs.humanoids.stompymini_config import MiniCfg, MiniCfgPPO
from sim.envs.humanoids.stompymini_env import MiniFreeEnv
Expand All @@ -25,27 +25,11 @@
from sim.utils.task_registry import TaskRegistry # noqa: E402

task_registry = TaskRegistry()

# Stompy
## Mini
task_registry.register("stompymini", MiniFreeEnv, MiniCfg(), MiniCfgPPO())
## Pro
task_registry.register("stompypro", StompyProFreeEnv, StompyProCfg(), StompyProCfgPPO())
task_registry.register("stompypro_standing", StompyProFreeEnv, StompyProStandingCfg(), StompyProCfgPPO())
## Micro
task_registry.register("stompymicro", StompyMicroEnv, StompyMicroCfg(), StompyMicroCfgPPO())
task_registry.register("stompymicro_standing", StompyMicroEnv, StompyMicroStandingCfg()
, StompyMicroCfgPPO())
task_registry.register("stompymicro_walking", StompyMicroEnv, StompyMicroWalkingCfg(), StompyMicroCfgPPO())

# Dora
task_registry.register("dora", DoraFreeEnv, DoraCfg(), DoraCfgPPO())

# Unitree
## h1
task_registry.register("h1", H1FreeEnv, H1Cfg(), H1CfgPPO())
## g1
task_registry.register("g1", G1FreeEnv, G1Cfg(), G1CfgPPO())

# XBotL
task_registry.register("XBotL_free", XBotLFreeEnv, XBotCfg(), XBotCfgPPO())
task_registry.register("stompymicro", StompyMicroEnv, StompyMicroCfg(), StompyMicroCfgPPO())
31 changes: 0 additions & 31 deletions sim/envs/base/base_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,34 +55,3 @@ def init_member_classes(obj):
setattr(obj, key, i_var)
# recursively init members of the attribute
BaseConfig.init_member_classes(i_var)

def __str__(self):
def format_value(value, indent=0):
if isinstance(value, (int, float, str, bool)):
return str(value)
elif isinstance(value, list):
return str(value)
elif isinstance(value, dict):
return "\n" + "\n".join(
f"{' ' * (indent + 1)}{k}: {format_value(v, indent + 1)}" for k, v in value.items()
)
elif hasattr(value, "__dict__"):
return "\n" + "\n".join(
f"{' ' * (indent + 1)}{k}: {format_value(getattr(value, k), indent + 1)}"
for k in dir(value)
if not k.startswith("__") and not callable(getattr(value, k))
)
else:
return str(value)

output = []
for attr in dir(self):
if not attr.startswith("__") and not callable(getattr(self, attr)):
value = getattr(self, attr)
formatted_value = format_value(value)
output.append(f"{attr}: {formatted_value}")

return "\n".join(output)

def __repr__(self):
return self.__str__()
100 changes: 25 additions & 75 deletions sim/envs/humanoids/stompymicro_config.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
"""Defines the environment configuration for the Getting up task"""

from typing import Any, Dict

from sim.env import robot_urdf_path
from sim.envs.base.legged_robot_config import ( # type: ignore
LeggedRobotCfg,
Expand All @@ -12,29 +10,7 @@
NUM_JOINTS = len(Robot.all_joints()) # 20


class ConfigMixin:
UPDATES: Dict[str, Any] = {}

@classmethod
def _update_recursive(cls, base_config, updates):
for key, value in updates.items():
if isinstance(value, dict) and hasattr(base_config, key):
setattr(base_config, key,
cls._update_recursive(getattr(base_config, key), value))
else:
setattr(base_config, key, value)
return base_config

def __new__(cls, updates: Dict[str, Any] = None):
config = super().__new__(cls)
config.__init__()
cls._update_recursive(config, cls.UPDATES)
if updates:
cls._update_recursive(config, updates)
return config


class StompyMicroCfg(LeggedRobotCfg, ConfigMixin):
class StompyMicroCfg(LeggedRobotCfg):
"""Configuration class for the Legs humanoid robot."""

class env(LeggedRobotCfg.env):
Expand Down Expand Up @@ -99,7 +75,7 @@ class terrain(LeggedRobotCfg.terrain):
restitution = 0.0

class noise:
add_noise = True
add_noise = False # pfb30 bring it back
noise_level = 0.6 # scales other values

class noise_scales: # pfb30 bring it back
Expand Down Expand Up @@ -152,12 +128,12 @@ class physx(LeggedRobotCfg.sim.physx):

class domain_rand(LeggedRobotCfg.domain_rand):
start_pos_noise = 0.01
randomize_friction = True
randomize_friction = False
friction_range = [0.1, 2.0]

randomize_base_mass = True
randomize_base_mass = False #True
added_mass_range = [-1.0, 1.0]
push_robots = True
push_robots = False #True
push_interval_s = 4
max_push_vel_xy = 0.2
max_push_ang_vel = 0.4
Expand Down Expand Up @@ -193,6 +169,23 @@ class rewards:
max_contact_force = 100 # forces above this value are penalized

class scales:
# # reference motion tracking
# joint_pos = 1.6
# feet_clearance = 1.6
# feet_contact_number = 1.2
# feet_air_time = 1.6
# foot_slip = -0.05
# feet_distance = 0.2
# knee_distance = 0.2
# # contact
# feet_contact_forces = -0.01
# # vel tracking
# tracking_lin_vel = 1.2
# tracking_ang_vel = 1.1
# vel_mismatch_exp = 0.5 # lin_z; ang x,y
# low_speed = 0.2
# track_vel_hard = 0.5

# base pos
default_joint_pos = 0.5
orientation = 1
Expand Down Expand Up @@ -223,50 +216,7 @@ class viewer:
lookat = [0, -2, 0]


NO_RAND = {
"domain_rand": {
"add_noise": False,
"randomize_friction": False,
"randomize_base_mass": False,
"push_robots": False,
"action_delay": 0.0,
}
}


class StompyMicroStandingCfg(StompyMicroCfg):
"""Configuration for StompyMicro standing task."""
UPDATES = NO_RAND


class StompyMicroWalkingCfg(StompyMicroCfg):
"""Configuration for StompyMicro walking task."""
UPDATES = dict({
"rewards": {
"scales": {
# reference motion tracking
"joint_pos": 1.6,
"feet_clearance": 1.6,
"feet_contact_number": 1.2,
# gait
"feet_air_time": 1.6,
"foot_slip": -0.05,
"feet_distance": 0.2,
"knee_distance": 0.2,
# contact
"feet_contact_forces": -0.01,
# vel tracking
"tracking_lin_vel": 1.2,
"tracking_ang_vel": 1.1,
"vel_mismatch_exp": 0.5,
"low_speed": 0.2,
"track_vel_hard": 0.5,
}
}
}, **NO_RAND)


class StompyMicroCfgPPO(LeggedRobotCfgPPO, ConfigMixin):
class StompyMicroCfgPPO(LeggedRobotCfgPPO):
seed = 5
runner_class_name = "OnPolicyRunner" # DWLOnPolicyRunner

Expand Down Expand Up @@ -295,6 +245,6 @@ class runner:
run_name = ""
# load and resume
resume = False
load_run = -1 # last run
checkpoint = -1 # last saved model
load_run = -1 # -1 = last run
checkpoint = -1 # -1 = last saved model
resume_path = None # updated from load_run and chkpt
3 changes: 2 additions & 1 deletion sim/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,8 @@ def play(args: argparse.Namespace) -> None:
env.commands[:, 1] = 0.0
env.commands[:, 2] = 0.0
env.commands[:, 3] = 0.0
obs, _, _, _, infos = env.step(actions.detach())
obs, critic_obs, rews, dones, infos = env.step(actions.detach())
print(f"IMU: {obs[0, (3 * env.num_actions + 5) + 3 : (3 * env.num_actions + 5) + 2 * 3]}")

if RENDER:
env.gym.fetch_results(env.sim, True)
Expand Down
13 changes: 6 additions & 7 deletions sim/requirements.txt
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
# requirements.txt

gdown
mediapy
torch
python-dotenv
h5py
gdown
matplotlib==3.3.4
mediapy
numpy==1.19.5
opencv-python==4.10.0.84
wandb
tensorboard==2.14.0
onnx
onnxscript
python-dotenv
tensorboard==2.14.0
torch
wandb
58 changes: 26 additions & 32 deletions sim/resources/stompymicro/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,11 +64,6 @@ class RightArm(Node):
elbow_pitch = "right_elbow_yaw" # FIXME: yaw vs pitch


class Arms(Node):
left = LeftArm()
right = RightArm()


class LeftLeg(Node):
hip_roll = "left_hip_roll"
hip_yaw = "left_hip_yaw"
Expand All @@ -91,12 +86,11 @@ class Legs(Node):


class Robot(Node):
height = 0.188
# rotation = [0., 0., -0.7071068, 0.7071068]
rotation = [0., 0., 0.7071068, 0.7071068]
# rotation = [0., 0., 0., 1.]
height = 0.21
rotation = [0.0, 0.0, 0, 1]

# arms = Arms()
# left_arm = LeftArm()
# right_arm = RightArm()
legs = Legs()

@classmethod
Expand All @@ -114,81 +108,81 @@ def default_standing(cls) -> Dict[str, float]:
cls.legs.right.knee_pitch: 0,
cls.legs.right.ankle_pitch: 0,
# Arms (adjust as needed)
# cls.arms.left.shoulder_pitch: 0,
# cls.arms.left.shoulder_yaw: 0.3,
# cls.arms.left.elbow_pitch: -0.6,
# cls.arms.right.shoulder_pitch: 0,
# cls.arms.right.shoulder_yaw: -0.3,
# cls.arms.right.elbow_pitch: -0.6,
# cls.left_arm.shoulder_pitch: 0,
# cls.left_arm.shoulder_yaw: 0.3,
# cls.left_arm.elbow_pitch: -0.6,
# cls.right_arm.shoulder_pitch: 0,
# cls.right_arm.shoulder_yaw: -0.3,
# cls.right_arm.elbow_pitch: -0.6,
}

@classmethod
def default_limits(cls) -> Dict[str, Dict[str, float]]:
return {
# left arm
cls.arms.left.shoulder_pitch: {
Robot.left_arm.shoulder_pitch: {
"lower": 2.04,
"upper": 3.06,
},
cls.arms.left.shoulder_yaw: {
Robot.left_arm.shoulder_yaw: {
"lower": -1,
"upper": 2,
},
cls.arms.left.elbow_pitch: {
Robot.left_arm.elbow_pitch: {
"lower": -2.06,
"upper": -1.08,
},
# right arm
cls.arms.right.shoulder_pitch: {
Robot.right_arm.shoulder_pitch: {
"lower": 2.619,
"upper": 3.621,
},
cls.arms.right.shoulder_yaw: {
Robot.right_arm.shoulder_yaw: {
"lower": -1.481,
"upper": 1,
},
cls.arms.right.elbow_pitch: {
Robot.right_arm.elbow_pitch: {
"lower": -3.819,
"upper": 3.821,
},
cls.legs.left.hip_pitch: {
Robot.legs.left.hip_pitch: {
"lower": -1.64,
"upper": 1.64,
},
cls.legs.left.hip_roll: {
Robot.legs.left.hip_roll: {
"lower": -4.0,
"upper": 1.0,
},
cls.legs.left.hip_yaw: {
Robot.legs.left.hip_yaw: {
"lower": 2.64,
"upper": 5.64,
},
cls.legs.left.knee_pitch: {
Robot.legs.left.knee_pitch: {
"lower": -2.5,
"upper": 0.5,
},
cls.legs.left.ankle_pitch: {
Robot.legs.left.ankle_pitch: {
"lower": -0.3,
"upper": 0.3,
},
# right leg
cls.legs.right.hip_pitch: {
Robot.legs.right.hip_pitch: {
"lower": 0.05,
"upper": 4.05,
},
cls.legs.right.hip_roll: {
Robot.legs.right.hip_roll: {
"lower": 2.25,
"upper": 4.49,
},
cls.legs.right.hip_yaw: {
Robot.legs.right.hip_yaw: {
"lower": 1.74,
"upper": 4.74,
},
cls.legs.right.knee_pitch: {
Robot.legs.right.knee_pitch: {
"lower": -0.5,
"upper": 2.5,
},
cls.legs.right.ankle_pitch: {
Robot.legs.right.ankle_pitch: {
"lower": -0.3,
"upper": 0.3,
},
Expand Down
Loading

0 comments on commit 972a2ee

Please sign in to comment.