diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py index 47136d6..04afd3d 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py @@ -74,8 +74,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 - self.rewards.applied_torque_limits.params["asset_cfg"].body_names = ["base"] self.rewards.action_rate_l2.weight = -0.01 # UNUESD self.rewards.action_l2.weight = 0.0 diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/fftai_gr1t1/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/fftai_gr1t1/rough_env_cfg.py index 7f63998..2aaf3a8 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/fftai_gr1t1/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/fftai_gr1t1/rough_env_cfg.py @@ -80,7 +80,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 self.rewards.action_rate_l2.weight = -0.005 # UNUESD self.rewards.action_l2.weight = 0.0 diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1/rough_env_cfg.py index 12ef464..0cf470a 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1/rough_env_cfg.py @@ -86,8 +86,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 - self.rewards.applied_torque_limits.params["asset_cfg"].body_names = ["trunk"] self.rewards.action_rate_l2.weight = -0.01 # UNUESD self.rewards.action_l2.weight = 0.0 diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1_amp/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1_amp/rough_env_cfg.py index bcf7011..46bddd0 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1_amp/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_a1_amp/rough_env_cfg.py @@ -77,7 +77,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 self.rewards.action_rate_l2.weight = 0 # UNUESD self.rewards.action_l2.weight = 0.0 diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_go2w/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_go2w/rough_env_cfg.py index 353ab4d..e4173c6 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_go2w/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_go2w/rough_env_cfg.py @@ -84,8 +84,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 - self.rewards.applied_torque_limits.params["asset_cfg"].body_names = ["base"] self.rewards.action_rate_l2.weight = -0.01 # UNUESD self.rewards.action_l2.weight = 0.0 diff --git a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_h1/rough_env_cfg.py b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_h1/rough_env_cfg.py index e6e779d..d4ca91a 100644 --- a/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_h1/rough_env_cfg.py +++ b/exts/robot_lab/robot_lab/tasks/locomotion/velocity/config/unitree_h1/rough_env_cfg.py @@ -76,7 +76,6 @@ def __post_init__(self): self.rewards.joint_vel_limits.weight = 0 # Action penalties - self.rewards.applied_torque_limits.weight = 0 self.rewards.action_rate_l2.weight = -0.005 # UNUESD self.rewards.action_l2.weight = 0.0