Skip to content

Commit

Permalink
saving new modle with inertia, training works
Browse files Browse the repository at this point in the history
  • Loading branch information
is2ac2 committed Jul 11, 2024
1 parent d414cc3 commit 03bbe47
Show file tree
Hide file tree
Showing 5 changed files with 1,360 additions and 97 deletions.
82 changes: 41 additions & 41 deletions sim/humanoid_gym/envs/only_legs_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,24 +32,24 @@ class env(LeggedRobotCfg.env):

class safety:
# safety factors
pos_limit = 1.0
vel_limit = 1.0
torque_limit = 1.0
pos_limit = .9
vel_limit = .9
torque_limit = .9

class asset(LeggedRobotCfg.asset):
file = str(stompy_urdf_path())
file = str(stompy_urdf_path(legs_only=True))

name = "stompy"

foot_name = "_foot_1_rmd_x4_24_mock_1_inner_rmd_x4_24_1"
knee_name = "_rmd_x8_90_mock_3_inner_rmd_x8_90_1"

termination_height = 0.23
termination_height = 0.23 # TODO: find a suitable value
default_feet_height = 0.0
terminate_after_contacts_on = ["link_upper_limb_assembly_7_dof_1_torso_1_top_skeleton_2"]
terminate_after_contacts_on = [] # TODO: find a part for this

penalize_contacts_on = []
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
flip_visual_attachments = False
replace_cylinder_with_capsule = False
fix_base_link = False
Expand All @@ -72,7 +72,7 @@ class terrain(LeggedRobotCfg.terrain):
restitution = 0.0

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

class noise_scales:
Expand All @@ -84,7 +84,7 @@ class noise_scales:
height_measurements = 0.1

class init_state(LeggedRobotCfg.init_state):
pos = [0.0, 0.0, 1.15]
pos = [0.0, 0.0, .72]

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

Expand All @@ -95,14 +95,14 @@ class init_state(LeggedRobotCfg.init_state):
class control(LeggedRobotCfg.control):
# PD Drive parameters:
stiffness = {
"shoulder": 200,
"elbow": 200,
"wrist": 200,
"hand": 200,
"torso": 200,
"hip": 200,
"ankle": 200,
"knee": 200,
"shoulder": 100,
"elbow": 100,
"wrist": 100,
"hand": 100,
"torso": 100,
"hip": 100,
"ankle": 100,
"knee": 100,
}
damping = {
"shoulder": 10,
Expand All @@ -126,11 +126,11 @@ class sim(LeggedRobotCfg.sim):

class physx(LeggedRobotCfg.sim.physx):
num_threads = 12
solver_type = 1 # 0: pgs, 1: tgs
solver_type = 0 # 0: pgs, 1: tgs
num_position_iterations = 4
num_velocity_iterations = 0
contact_offset = 0.01 # [m]
rest_offset = -0.02 # [m]
num_velocity_iterations = 1
contact_offset = 0.0 # [m]
rest_offset = 0 #-0.02 # [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
Expand All @@ -139,12 +139,12 @@ class physx(LeggedRobotCfg.sim.physx):
contact_collection = 2

class domain_rand:
randomize_friction = True
randomize_friction = False
friction_range = [0.1, 2.0]

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

class scales:
# reference motion tracking
joint_pos = 1.6
feet_clearance = 1.0
feet_contact_number = 1.2
# gait
feet_air_time = 1.0
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
# # reference motion tracking
# joint_pos = 1.6
# feet_clearance = 1.0
# feet_contact_number = 1.2
# # gait
# feet_air_time = 1.0
# 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

# above this was removed
# base pos
Expand Down
34 changes: 17 additions & 17 deletions sim/humanoid_gym/envs/stompy_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -178,23 +178,23 @@ class rewards:
max_contact_force = 400 # forces above this value are penalized

class scales:
# reference motion tracking
joint_pos = 1.6
feet_clearance = 1.0
feet_contact_number = 1.2
# gait
feet_air_time = 1.0
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
# # reference motion tracking
# joint_pos = 1.6
# feet_clearance = 1.0
# feet_contact_number = 1.2
# # gait
# feet_air_time = 1.0
# 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

# above this was removed
# base pos
Expand Down
10 changes: 5 additions & 5 deletions sim/scripts/create_fixed_torso.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,16 +3,16 @@

import xml.etree.ElementTree as ET

from sim.stompy.joints import StompyFixed
from sim.stompy_legs.joints import Stompy

STOMPY_URDF = "sim/stompy/robot.urdf"
STOMPY_URDF = "sim/stompy_legs/robot.urdf"


def update_urdf() -> None:
tree = ET.parse(STOMPY_URDF)
root = tree.getroot()
stompy = StompyFixed()

stompy = Stompy()
print(stompy.default_standing())
revolute_joints = set(stompy.default_standing().keys())
joint_limits = stompy.default_limits()

Expand All @@ -30,7 +30,7 @@ def update_urdf() -> None:
limit.set("upper", upper)

# Save the modified URDF to a new file
tree.write("sim/stompy/robot_fixed.urdf")
tree.write("sim/stompy_legs/robot_fixed.urdf")


if __name__ == "__main__":
Expand Down
68 changes: 34 additions & 34 deletions sim/stompy_legs/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,70 +86,70 @@ def default_positions(cls) -> Dict[str, float]:
def default_standing(cls) -> Dict[str, float]:
return {
# legs
Stompy.legs.left.hip_pitch: -0.12,
Stompy.legs.left.hip_roll: 1.44,
Stompy.legs.left.hip_yaw: -1.19,
Stompy.legs.left.knee_pitch: -2.32,
Stompy.legs.left.ankle_pitch: 0.56,
Stompy.legs.left.ankle_roll: -2.64,
Stompy.legs.right.hip_pitch: -4.33,
Stompy.legs.right.hip_roll: 3.14,
Stompy.legs.right.hip_yaw: -1.13,
Stompy.legs.right.knee_pitch: -1.95,
Stompy.legs.right.ankle_pitch: 0.62,
Stompy.legs.right.ankle_roll: -2.64,
Stompy.legs.left.hip_pitch: 1.61,
Stompy.legs.left.hip_roll: 0,
Stompy.legs.left.hip_yaw: 1,
Stompy.legs.left.knee_pitch: 2.05,
Stompy.legs.left.ankle_pitch: 0.33,
Stompy.legs.left.ankle_roll: 1.73,
Stompy.legs.right.hip_pitch: 0,
Stompy.legs.right.hip_roll: -1.6,
Stompy.legs.right.hip_yaw: -2.15,
Stompy.legs.right.knee_pitch: 2.16,
Stompy.legs.right.ankle_pitch: 0.5,
Stompy.legs.right.ankle_roll: 1.72,
}

@classmethod
def default_limits(cls) -> Dict[str, Dict[str, float]]:
return {
Stompy.legs.left.hip_pitch: {
"lower": -1.32,
"upper": 0.69,
"lower": 0.5,
"upper": 2.69,
},
Stompy.legs.left.hip_roll: {
"lower": 1.13,
"upper": 2.14,
"lower": -0.5,
"upper": 0.5,
},
Stompy.legs.left.hip_yaw: {
"lower": -2.2,
"upper": -1.19,
"lower": 0.5,
"upper": 1.19,
},
Stompy.legs.left.knee_pitch: {
"lower": -3.14,
"upper": -2.2,
"lower": 0.5,
"upper": 2.1,
},
Stompy.legs.left.ankle_pitch: {
"lower": 0.44,
"lower": 0.0,
"upper": 1.13,
},
Stompy.legs.left.ankle_roll: {
"lower": -3.08,
"upper": -2.26,
"lower": 1.3,
"upper": 2,
},
Stompy.legs.right.hip_pitch: {
"lower": -5.00,
"upper": -3.83,
"lower": -1,
"upper": 1,
},
Stompy.legs.right.hip_roll: {
"lower": 2.39,
"upper": 3.33,
"lower": -2.39,
"upper": -1,
},
Stompy.legs.right.hip_yaw: {
"lower": -1.13,
"upper": -0.69,
"lower": -2.2,
"upper": -1,
},
Stompy.legs.right.knee_pitch: {
"lower": -1.95,
"upper": -1.00,
"lower": 1.84,
"upper": 3,
},
Stompy.legs.right.ankle_pitch: {
"lower": 0.00,
"lower": -0.5,
"upper": 0.94,
},
Stompy.legs.right.ankle_roll: {
"lower": -3.00,
"upper": -2.14,
"lower": 1,
"upper": 2,
},
}

Expand Down
Loading

0 comments on commit 03bbe47

Please sign in to comment.