From 73dee0ca41a61c9df4eb7e52d2bce0bdd76cec6c Mon Sep 17 00:00:00 2001 From: budzianowski Date: Sun, 8 Dec 2024 20:31:19 -0800 Subject: [PATCH] update to even lower efforts --- sim/envs/humanoids/gpr_config.py | 2 +- sim/resources/gpr/joints.py | 10 +++++----- sim/resources/gpr/robot_fixed.urdf | 20 ++++++++++---------- 3 files changed, 16 insertions(+), 16 deletions(-) diff --git a/sim/envs/humanoids/gpr_config.py b/sim/envs/humanoids/gpr_config.py index 041a8426..91d66d7f 100644 --- a/sim/envs/humanoids/gpr_config.py +++ b/sim/envs/humanoids/gpr_config.py @@ -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" diff --git a/sim/resources/gpr/joints.py b/sim/resources/gpr/joints.py index 65d7e356..b6c83812 100755 --- a/sim/resources/gpr/joints.py +++ b/sim/resources/gpr/joints.py @@ -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 diff --git a/sim/resources/gpr/robot_fixed.urdf b/sim/resources/gpr/robot_fixed.urdf index 9043495a..c1e2aef7 100644 --- a/sim/resources/gpr/robot_fixed.urdf +++ b/sim/resources/gpr/robot_fixed.urdf @@ -95,7 +95,7 @@ - + @@ -124,7 +124,7 @@ - + @@ -211,7 +211,7 @@ - + @@ -240,7 +240,7 @@ - + @@ -327,7 +327,7 @@ - + @@ -356,7 +356,7 @@ - + @@ -443,7 +443,7 @@ - + @@ -472,7 +472,7 @@ - + @@ -559,7 +559,7 @@ - + @@ -588,7 +588,7 @@ - +