Skip to content

Commit

Permalink
update efforts
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed Dec 9, 2024
1 parent cca588a commit 092511d
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 12 deletions.
2 changes: 1 addition & 1 deletion sim/envs/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from sim.envs.humanoids.g1_config import G1Cfg, G1CfgPPO
from sim.envs.humanoids.g1_env import G1FreeEnv
from sim.envs.humanoids.gpr_env import GprFreeEnv
from sim.envs.humanoids.grp_config import GprCfg, GprCfgPPO, GprStandingCfg
from sim.envs.humanoids.gpr_config import GprCfg, GprCfgPPO, GprStandingCfg
from sim.envs.humanoids.h1_config import H1Cfg, H1CfgPPO
from sim.envs.humanoids.h1_env import H1FreeEnv
from sim.envs.humanoids.xbot_config import XBotCfg, XBotCfgPPO
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ class ranges:

class rewards:
# quite important to keep it right
base_height_target = 0.63
base_height_target = Robot.height
min_dist = 0.2
max_dist = 0.5
# put some settings here for LLM parameter tuning
Expand Down Expand Up @@ -219,7 +219,7 @@ class rewards:
# put some settings here for LLM parameter tuning
target_joint_pos_scale = 0.17 # rad
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)
Expand Down
6 changes: 3 additions & 3 deletions sim/resources/gpr/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -179,10 +179,10 @@ def damping(cls) -> Dict[str, float]:
def effort(cls) -> Dict[str, float]:
return {
"hip_y": 120,
"hip_x": 100,
"hip_z": 100,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 50,
"ankle_y": 17,
}

# # vel_limits
Expand Down
12 changes: 6 additions & 6 deletions sim/resources/gpr/robot_fixed.urdf
Original file line number Diff line number Diff line change
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="100" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="60" 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="100" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="60" 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="100" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="60" 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="100" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="60" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 1" />
</joint>
<link name="leg2_shell_2">
Expand Down Expand Up @@ -559,7 +559,7 @@
<origin xyz="1.0767167917674625e-08 -0.29999999865410376 0.027200000000000002" rpy="-3.1415926071795868 2.220446049250313e-16 -3.1415926071795868" />
<parent link="leg3_shell22" />
<child link="foot3" />
<limit effort="50" velocity="10" lower="-0.6981317" upper="0.6981317" />
<limit effort="17" velocity="10" lower="-0.6981317" upper="0.6981317" />
<axis xyz="0 0 1" />
</joint>
<link name="foot3">
Expand Down Expand Up @@ -588,7 +588,7 @@
<origin xyz="0.0 -0.30000000004641003 0.07019999118206069" rpy="9.282041357749903e-08 0.0 0.0" />
<parent link="leg3_shell2" />
<child link="foot1" />
<limit effort="50" velocity="10" lower="-0.6981317" upper="0.6981317" />
<limit effort="17" velocity="10" lower="-0.6981317" upper="0.6981317" />
<axis xyz="0 0 -1" />
</joint>
<link name="foot1">
Expand Down

0 comments on commit 092511d

Please sign in to comment.