Skip to content

Commit

Permalink
update to even lower efforts
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed Dec 9, 2024
1 parent 57fcfea commit 73dee0c
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 16 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 @@ -30,7 +30,7 @@ class safety(LeggedRobotCfg.safety):
# safety factors
pos_limit = 1.0
vel_limit = 1.0
torque_limit = 0.6
torque_limit = 1.0

class asset(LeggedRobotCfg.asset):
name = "gpr"
Expand Down
10 changes: 5 additions & 5 deletions sim/resources/gpr/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -178,11 +178,11 @@ def damping(cls) -> Dict[str, float]:
@classmethod
def effort(cls) -> Dict[str, float]:
return {
"hip_y": 120,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 26,
"hip_y": 40,
"hip_x": 20,
"hip_z": 20,
"knee": 40,
"ankle_y": 17,
}

# # vel_limits
Expand Down
20 changes: 10 additions & 10 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="40" 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="40" 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="40" 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="40" velocity="10" lower="0" upper="1.57" />
<axis xyz="0 0 1" />
</joint>
<link name="leg3_shell22">
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="26" 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="26" 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 73dee0c

Please sign in to comment.