Skip to content

Commit

Permalink
update values
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed Dec 9, 2024
1 parent 6e113ce commit 57fcfea
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 12 deletions.
8 changes: 4 additions & 4 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 = 0.6

class asset(LeggedRobotCfg.asset):
name = "gpr"
Expand All @@ -51,8 +51,8 @@ class asset(LeggedRobotCfg.asset):
fix_base_link = False

class terrain(LeggedRobotCfg.terrain):
# mesh_type = "plane"
mesh_type = "trimesh"
mesh_type = "plane"
# mesh_type = "trimesh"
curriculum = False
# rough terrain only:
measure_heights = False
Expand Down Expand Up @@ -152,7 +152,7 @@ class rewards:
target_joint_pos_scale = 0.17 # rad
target_feet_height = 0.05 # m

cycle_time = 0.5 # sec
cycle_time = 0.25 # 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
12 changes: 6 additions & 6 deletions sim/resources/gpr/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,11 +156,11 @@ def default_limits(cls) -> Dict[str, Dict[str, float]]:
@classmethod
def stiffness(cls) -> Dict[str, float]:
return {
"hip_y": 240,
"hip_x": 120,
"hip_z": 120,
"knee": 240,
"ankle_y": 34,
"hip_y": 120,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 17,
}

# d_gains
Expand All @@ -182,7 +182,7 @@ def effort(cls) -> Dict[str, float]:
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 17,
"ankle_y": 26,
}

# # vel_limits
Expand Down
4 changes: 2 additions & 2 deletions sim/resources/gpr/robot_fixed.urdf
Original file line number Diff line number Diff line change
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="17" velocity="10" lower="-0.6981317" upper="0.6981317" />
<limit effort="26" 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="17" velocity="10" lower="-0.6981317" upper="0.6981317" />
<limit effort="26" velocity="10" lower="-0.6981317" upper="0.6981317" />
<axis xyz="0 0 -1" />
</joint>
<link name="foot1">
Expand Down

0 comments on commit 57fcfea

Please sign in to comment.