Skip to content

Commit

Permalink
MICRO Stompy (#82)
Browse files Browse the repository at this point in the history
* stompy micro upload

* comment out joints

* revert stompymini joints

* file name error renamed joint to joints.py

* got joints.py done i think

* config and env added for stompy micro, but getted failed to resolve mesh errors

* fixed ankle/foot rotate

* fixed hip

* fix yaw dimensions

* add stompymicro meshes

* fix gdown

* raise z

* standing pose

* fix reset height

* Update sim/resources/stompymicro/joints.py

Co-authored-by: Paweł Budzianowski <[email protected]>

* Update sim/envs/humanoids/stompymicro_config.py

Co-authored-by: Paweł Budzianowski <[email protected]>

* Incorrect gdrive location for stompymicro, should be in gdrive's stompymicro/meshes rather than stompymicro/

* Fixed format

* Over-indenting bug fix

* Added required docstring to stompymicro's joints

* Added __init__.py files to stompymini and stompymicro

* Added wandb as known third party for isort

* commented out walking reward, to only stand

* update the names in the stiffness method

* fix damping (d_gains) values and declarations

* wtf

* fix gait reward

* add arm joints

* make format

* fixed urdf

* reset joint names

* added full body

* significantly increased stiffness (now it sort of stands)

---------

Co-authored-by: Advait Patel <[email protected]>
Co-authored-by: Paweł Budzianowski <[email protected]>
Co-authored-by: Henri <[email protected]>
  • Loading branch information
4 people authored Sep 26, 2024
1 parent 89d8d92 commit 67f40d1
Show file tree
Hide file tree
Showing 12 changed files with 1,713 additions and 2 deletions.
Binary file added policy_1.pt
Binary file not shown.
1 change: 1 addition & 0 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ module = [
[tool.isort]

profile = "black"
known_third_party = ["wandb"]

[tool.ruff]

Expand Down
2 changes: 2 additions & 0 deletions sim/env.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@


def model_dir(robotname: str) -> Path:
print(os.getcwd())

return Path(os.environ.get("MODEL_DIR", "sim/resources/" + robotname))


Expand Down
5 changes: 4 additions & 1 deletion sim/envs/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
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, 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
from sim.envs.humanoids.stompypro_config import StompyProCfg, StompyProStandingCfg, StompyProCfgPPO
Expand All @@ -29,4 +31,5 @@
task_registry.register("dora", DoraFreeEnv, DoraCfg(), DoraCfgPPO())
task_registry.register("h1", H1FreeEnv, H1Cfg(), H1CfgPPO())
task_registry.register("g1", G1FreeEnv, G1Cfg(), G1CfgPPO())
task_registry.register("xbot", XBotLFreeEnv, XBotCfg(), XBotCfgPPO())
task_registry.register("XBotL_free", XBotLFreeEnv, XBotCfg(), XBotCfgPPO())
task_registry.register("stompymicro", StompyMicroEnv, StompyMicroCfg(), StompyMicroCfgPPO())
259 changes: 259 additions & 0 deletions sim/envs/humanoids/stompymicro_config.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,259 @@
"""Defines the environment configuration for the Getting up task"""

from sim.env import robot_urdf_path
from sim.envs.base.legged_robot_config import ( # type: ignore
LeggedRobotCfg,
LeggedRobotCfgPPO,
)
from sim.resources.stompymicro.joints import Robot

NUM_JOINTS = len(Robot.all_joints()) # 20


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

class env(LeggedRobotCfg.env):
# change the observation dim
frame_stack = 15
c_frame_stack = 3
num_single_obs = 11 + NUM_JOINTS * 3
num_observations = int(frame_stack * num_single_obs)
single_num_privileged_obs = 25 + NUM_JOINTS * 4
num_privileged_obs = int(c_frame_stack * single_num_privileged_obs)
num_actions = NUM_JOINTS
num_envs = 4096
episode_length_s = 24 # episode length in seconds
use_ref_actions = False

class safety:
# safety factors
pos_limit = 1.0
vel_limit = 1.0
torque_limit = 0.85
terminate_after_contacts_on = []

class asset(LeggedRobotCfg.asset):
name = "stompymicro"
file = str(robot_urdf_path(name))

foot_name = ["DRIVING_ROTOR_PLATE_9", "DRIVING_ROTOR_PLATE_10"]
knee_name = ["DRIVING_ROTOR_PLATE_7", "DRIVING_ROTOR_PLATE_8"]

termination_height = 0.1

default_feet_height = 0.03

terminate_after_contacts_on = []

penalize_contacts_on = []
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
flip_visual_attachments = False
replace_cylinder_with_capsule = False
fix_base_link = False

class terrain(LeggedRobotCfg.terrain):
mesh_type = "plane"
# mesh_type = 'trimesh'
curriculum = False
# rough terrain only:
measure_heights = False
static_friction = 0.6
dynamic_friction = 0.6
terrain_length = 8.0
terrain_width = 8.0
num_rows = 10 # number of terrain rows (levels)
num_cols = 10 # number of terrain cols (types)
max_init_terrain_level = 10 # starting curriculum state
# plane; obstacles; uniform; slope_up; slope_down, stair_up, stair_down
terrain_proportions = [0.2, 0.2, 0.4, 0.1, 0.1, 0, 0]
restitution = 0.0

class noise:
add_noise = True
noise_level = 0.6 # scales other values

class noise_scales:
dof_pos = 0.05
dof_vel = 0.5
ang_vel = 0.1
lin_vel = 0.05
quat = 0.03
height_measurements = 0.1

class init_state(LeggedRobotCfg.init_state):
pos = [0.0, 0.0, Robot.height] # add z value to lift the robot
# setting the right rotation
# quat_from_euler_xyz(torch.tensor(1.57), torch.tensor(0), torch.tensor(-1.57))
rot = Robot.rotation

default_joint_angles = {k: 0.0 for k in Robot.all_joints()}

default_positions = Robot.default_standing()
for joint in default_positions:
default_joint_angles[joint] = default_positions[joint]

class control(LeggedRobotCfg.control):
# PD Drive parameters:
stiffness = Robot.stiffness()
damping = Robot.damping()
# action scale: target angle = actionScale * action + defaultAngle
action_scale = 0.25
# decimation: Number of control action updates @ sim DT per policy DT
decimation = 10 # 100hz

class sim(LeggedRobotCfg.sim):
dt = 0.001 # 1000 Hz
substeps = 1 # 2
up_axis = 1 # 0 is y, 1 is z

class physx(LeggedRobotCfg.sim.physx):
num_threads = 10
solver_type = 1 # 0: pgs, 1: tgs
num_position_iterations = 4
num_velocity_iterations = 1
contact_offset = 0.01 # [m]
rest_offset = 0.0 # [m]
bounce_threshold_velocity = 0.1 # [m/s]
max_depenetration_velocity = 1.0
max_gpu_contact_pairs = 2**23 # 2**24 -> needed for 8000 envs and more
default_buffer_size_multiplier = 5
# 0: never, 1: last sub-step, 2: all sub-steps (default=2)
contact_collection = 2

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

randomize_base_mass = True
added_mass_range = [-1.0, 1.0]
push_robots = True
push_interval_s = 4
max_push_vel_xy = 0.2
max_push_ang_vel = 0.4
dynamic_randomization = 0.05

class commands(LeggedRobotCfg.commands):
# Vers: lin_vel_x, lin_vel_y, ang_vel_yaw, heading (in heading mode ang_vel_yaw is recomputed from heading error)
num_commands = 4
resampling_time = 8.0 # time before command are changed[s]
heading_command = True # if true: compute ang vel command from heading error

class ranges:
lin_vel_x = [-0.3, 0.6] # min max [m/s]
lin_vel_y = [-0.3, 0.3] # min max [m/s]
ang_vel_yaw = [-0.3, 0.3] # min max [rad/s]
heading = [-3.14, 3.14]

class rewards:
base_height_target = 0.78
min_dist = 0.25
max_dist = 0.5

# put some settings here for LLM parameter tuning
target_joint_pos_scale = 0.17 # rad
target_feet_height = 0.05 # m
cycle_time = 0.4 # sec
# if true negative total rewards are clipped at zero (avoids early termination problems)
only_positive_rewards = True
# tracking reward = exp(error*sigma)
tracking_sigma = 5.0
max_contact_force = 400 # forces above this value are penalized

class 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 # lin_z; ang x,y
# low_speed = 0.2
# track_vel_hard = 0.5
# 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 # lin_z; ang x,y
low_speed = 0.2
track_vel_hard = 0.5

# base pos
default_joint_pos = 0.5
orientation = 1
base_height = 0.2
base_acc = 0.2
# energy
action_smoothness = -0.002
torques = -1e-5
dof_vel = -5e-4
dof_acc = -1e-7
collision = -1.0

class normalization:
class obs_scales:
lin_vel = 2.0
ang_vel = 1.0
dof_pos = 1.0
dof_vel = 0.05
quat = 1.0
height_measurements = 5.0

clip_observations = 18.0
clip_actions = 18.0

class viewer:
ref_env = 0
pos = [4, -4, 2]
lookat = [0, -2, 0]


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

class policy:
init_noise_std = 1.0
actor_hidden_dims = [512, 256, 128]
critic_hidden_dims = [768, 256, 128]

class algorithm(LeggedRobotCfgPPO.algorithm):
entropy_coef = 0.001
learning_rate = 1e-5
num_learning_epochs = 2
gamma = 0.994
lam = 0.9
num_mini_batches = 4

class runner:
policy_class_name = "ActorCritic"
algorithm_class_name = "PPO"
num_steps_per_env = 60 # per iteration
max_iterations = 5001 # number of policy updates

# logging
save_interval = 100 # check for potential saves every this many iterations
experiment_name = "StompyMicro"
run_name = ""
# load and resume
resume = False
load_run = -1 # -1 = last run
checkpoint = -1 # -1 = last saved model
resume_path = None # updated from load_run and chkpt
Loading

0 comments on commit 67f40d1

Please sign in to comment.