Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Safe gpr params #130

Closed
wants to merge 12 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified examples/walking_policy.pt
Binary file not shown.
12 changes: 6 additions & 6 deletions sim/envs/humanoids/gpr_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class safety(LeggedRobotCfg.safety):
# safety factors
pos_limit = 1.0
vel_limit = 1.0
torque_limit = 0.85
torque_limit = 1.0

class asset(LeggedRobotCfg.asset):
name = "gpr"
Expand Down Expand Up @@ -123,7 +123,7 @@ class domain_rand(LeggedRobotCfg.domain_rand):

randomize_base_mass = True
added_mass_range = [-3.0, 3.0]
push_robots = False
push_robots = True
push_interval_s = 4
max_push_vel_xy = 0.2
max_push_ang_vel = 0.4
Expand All @@ -150,14 +150,14 @@ class rewards:
max_dist = 0.5
# put some settings here for LLM parameter tuning
target_joint_pos_scale = 0.17 # rad
target_feet_height = 0.06 # m
target_feet_height = 0.05 # m

cycle_time = 0.64 # sec
cycle_time = 0.5 # 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 = 700 # forces above this value are penalized
max_contact_force = 400 # forces above this value are penalized

class scales:
# reference motion tracking
Expand Down Expand Up @@ -213,7 +213,7 @@ class GprStandingCfg(GprCfg):

class rewards:
# quite important to keep it right
base_height_target = 1.06
base_height_target = Robot.height
min_dist = 0.2
max_dist = 0.5
# put some settings here for LLM parameter tuning
Expand Down
3 changes: 3 additions & 0 deletions sim/model_export.py
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,8 @@ def get_actor_policy(model_path: str, cfg: ActorCfg) -> Tuple[nn.Module, dict, T
num_actions = a_model.num_actions
num_observations = a_model.num_observations

default_standing = list(a_model.robot.default_standing().values())

return (
a_model,
{
Expand All @@ -250,6 +252,7 @@ def get_actor_policy(model_path: str, cfg: ActorCfg) -> Tuple[nn.Module, dict, T
"robot_damping": robot_damping,
"num_actions": num_actions,
"num_observations": num_observations,
"default_standing": default_standing,
},
input_tensors,
)
Expand Down
30 changes: 15 additions & 15 deletions sim/resources/gpr/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,33 +156,33 @@ def default_limits(cls) -> Dict[str, Dict[str, float]]:
@classmethod
def stiffness(cls) -> Dict[str, float]:
return {
"hip_y": 120,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 17,
"hip_y": 100, # 04
"hip_x": 40, # 03
"hip_z": 40, # 03
"knee": 100, # 04
"ankle_y": 17, # 02
}

# d_gains
@classmethod
def damping(cls) -> Dict[str, float]:
return {
"hip_y": 10,
"hip_x": 5,
"hip_z": 5,
"knee": 10,
"ankle_y": 5,
"hip_y": 10, # 04
"hip_x": 10, # 03
"hip_z": 10, # 03
"knee": 10, # 04
"ankle_y": 5, # 02
}

# # pos_limits
@classmethod
def effort(cls) -> Dict[str, float]:
return {
"hip_y": 120,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 17,
"hip_y": 30, # 04
"hip_x": 20, # 03
"hip_z": 20, # 03
"knee": 30, # 04
"ankle_y": 17, # 02
}

# # vel_limits
Expand Down
18 changes: 9 additions & 9 deletions sim/resources/gpr/robot_fixed.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@
<origin xyz="-0.008010608503738428 -0.43201043179234816 0.0877000068648673" rpy="-3.1415925071795874 4.641020678874952e-08 -3.1415926535897913" />
<parent link="body1-part" />
<child link="leg0_shell" />
<limit effort="120" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="30" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 -1" />
</joint>
<link name="leg0_shell">
Expand Down Expand Up @@ -124,7 +124,7 @@
<origin xyz="-0.008010600340183055 -0.4320104467591277 -0.08819999313513187" rpy="9.99999991702083e-08 4.641020678874952e-08 -3.1415926535897913" />
<parent link="body1-part" />
<child link="leg0_shell_2" />
<limit effort="120" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="30" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 -1" />
</joint>
<link name="leg0_shell_2">
Expand Down Expand Up @@ -211,7 +211,7 @@
<origin xyz="0.02649999999999997 -1.5165911463888016e-09 -0.06950000151659115" rpy="-1.5707963 0.0 1.5707963" />
<parent link="leg0_shell" />
<child link="leg1_shell" />
<limit effort="60" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="20" velocity="10" lower="-0.34906585" upper="3.1852259" />
<axis xyz="0 0 1" />
</joint>
<link name="leg1_shell">
Expand Down Expand Up @@ -240,7 +240,7 @@
<origin xyz="0.02649999999999997 -1.5165911463888016e-09 -0.06950000151659115" rpy="1.5707963 -4.641020634466031e-08 -1.5707963535897922" />
<parent link="leg0_shell_2" />
<child link="leg1_shell3" />
<limit effort="60" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="20" velocity="10" lower="-0.34906585" upper="3.1852259" />
<axis xyz="0 0 1" />
</joint>
<link name="leg1_shell3">
Expand Down Expand Up @@ -327,7 +327,7 @@
<origin xyz="-0.15649999999999997 0.0 0.027499998483408852" rpy="-0.0 1.5707963 0.0" />
<parent link="leg1_shell" />
<child link="leg2_shell" />
<limit effort="60" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="20" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 1" />
</joint>
<link name="leg2_shell">
Expand Down Expand Up @@ -356,7 +356,7 @@
<origin xyz="-0.15649999999999997 0.0 0.027499998483408852" rpy="-3.1415926535897922 -1.5707962732050302 0.0" />
<parent link="leg1_shell3" />
<child link="leg2_shell_2" />
<limit effort="60" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="20" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 1" />
</joint>
<link name="leg2_shell_2">
Expand Down Expand Up @@ -443,7 +443,7 @@
<origin xyz="0.0 0.0342 -0.14250000009378214" rpy="1.5707963000000003 0.0 0.0" />
<parent link="leg2_shell" />
<child link="leg3_shell2" />
<limit effort="120" velocity="10" lower="-1.57" upper="0" />
<limit effort="30" velocity="10" lower="-1.57" upper="0" />
<axis xyz="0 0 1" />
</joint>
<link name="leg3_shell2">
Expand Down Expand Up @@ -472,7 +472,7 @@
<origin xyz="0.0 0.0342 -0.14250000009378214" rpy="1.5707963000000003 0.0 0.0" />
<parent link="leg2_shell_2" />
<child link="leg3_shell22" />
<limit effort="120" velocity="10" lower="0" upper="1.57" />
<limit effort="30" velocity="10" lower="0" upper="1.57" />
<axis xyz="0 0 1" />
</joint>
<link name="leg3_shell22">
Expand Down Expand Up @@ -613,4 +613,4 @@
<origin xyz="0.021026404502789243 -0.018472020400304597 -0.01930430937248649" rpy="0 0 0" />
</inertial>
</link>
</robot>
</robot>
4 changes: 2 additions & 2 deletions sim/sim2sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -319,7 +319,7 @@ def run_mujoco(

policy_cfg = ActorCfg(embodiment=args.embodiment)
if args.embodiment == "gpr":
policy_cfg.cycle_time = 0.25
policy_cfg.cycle_time = 0.5
cfg = Sim2simCfg(
sim_duration=10.0,
dt=0.001,
Expand All @@ -337,7 +337,7 @@ def run_mujoco(
cycle_time=policy_cfg.cycle_time,
)

if args.load_model.endswith(".kinfer"):
if args.load_model.endswith(".kinfer") or args.load_model.endswith(".onnx"):
policy = ONNXModel(args.load_model)
else:
actor_model, sim2sim_info, input_tensors = get_actor_policy(args.load_model, policy_cfg)
Expand Down
Loading