Skip to content

Commit

Permalink
update efforts
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed Dec 14, 2024
1 parent 3bdd2a9 commit 72076c5
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 33 deletions.
2 changes: 1 addition & 1 deletion sim/envs/humanoids/gpr_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ class rewards:
target_joint_pos_scale = 0.17 # rad
target_feet_height = 0.05 # m

cycle_time = 0.64 # sec
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)
Expand Down
4 changes: 2 additions & 2 deletions sim/resources/gpr/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ def damping(cls) -> Dict[str, float]:
"ankle_y": 5,
}

# # pos_limits
# effort_limits
@classmethod
def effort(cls) -> Dict[str, float]:
return {
Expand All @@ -166,7 +166,7 @@ def effort(cls) -> Dict[str, float]:
"ankle_y": 17,
}

# # vel_limits
# vel_limits
@classmethod
def velocity(cls) -> Dict[str, float]:
return {"hip": 10, "knee": 10, "ankle": 10}
Expand Down
38 changes: 8 additions & 30 deletions sim/resources/gpr/robot_fixed.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -11,28 +11,6 @@
<parent link="base" />
<child link="body1-part" />
</joint>
<link name="imu_link">
<visual>
<geometry>
<box size="0.3 0.01 0.01"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
</link>
<joint
name="imu_joint"
type="fixed"
dont_collapse="true">
<origin
xyz="0.0 0.0 -0.13"
rpy="0 0 0" />
<parent
link="base" />
<child
link="imu_link" />
</joint>
<link name="body1-part">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
Expand Down Expand Up @@ -117,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="40" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="60" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 -1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg0_shell">
Expand Down Expand Up @@ -146,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="40" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="60" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 -1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg0_shell_2">
Expand Down Expand Up @@ -233,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="20" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="40" velocity="10" lower="-0.34906585" upper="3.1852259" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg1_shell">
Expand Down Expand Up @@ -262,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="20" velocity="10" lower="-0.34906585" upper="3.1852259" />
<limit effort="40" velocity="10" lower="-0.34906585" upper="3.1852259" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg1_shell3">
Expand Down Expand Up @@ -349,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="20" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="40" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg2_shell">
Expand Down Expand Up @@ -378,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="20" velocity="10" lower="-1.5707963" upper="1.5707963" />
<limit effort="40" velocity="10" lower="-1.5707963" upper="1.5707963" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg2_shell_2">
Expand Down Expand Up @@ -465,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="40" velocity="10" lower="-1.57" upper="0" />
<limit effort="60" velocity="10" lower="-1.57" upper="0" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg3_shell2">
Expand Down Expand Up @@ -494,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="40" velocity="10" lower="0" upper="1.57" />
<limit effort="60" velocity="10" lower="0" upper="1.57" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0" /></joint>
<link name="leg3_shell22">
Expand Down

0 comments on commit 72076c5

Please sign in to comment.