Unverified Commit a61e262d authored by David Hoeller's avatar David Hoeller Committed by GitHub

Tunes rewards for A1 locomotion environment (#271)

# Description

This MR tunes the A1 locomotion environment.

Fixes # (issue)

## Type of change

- New feature (non-breaking change which adds functionality)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent 40c5f4df
...@@ -60,6 +60,7 @@ UNITREE_A1_CFG = ArticulationCfg( ...@@ -60,6 +60,7 @@ UNITREE_A1_CFG = ArticulationCfg(
velocity_limit=21.0, velocity_limit=21.0,
stiffness=25.0, stiffness=25.0,
damping=0.5, damping=0.5,
friction=0.0,
), ),
}, },
) )
......
...@@ -5,29 +5,18 @@ ...@@ -5,29 +5,18 @@
from omni.isaac.orbit.utils import configclass from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit_tasks.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg from .rough_env_cfg import UnitreeA1RoughEnvCfg
##
# Pre-defined configs
##
from omni.isaac.orbit.assets.config.unitree import UNITREE_A1_CFG # isort: skip
@configclass @configclass
class UnitreeA1FlatEnvCfg(LocomotionVelocityRoughEnvCfg): class UnitreeA1FlatEnvCfg(UnitreeA1RoughEnvCfg):
def __post_init__(self): def __post_init__(self):
# post init of parent # post init of parent
super().__post_init__() super().__post_init__()
# switch robot to unitree a1
self.scene.robot = UNITREE_A1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# reduce action scale
self.actions.joint_pos.scale = 0.25
# override rewards # override rewards
self.rewards.flat_orientation_l2.weight = -2.5 self.rewards.flat_orientation_l2.weight = -2.5
self.rewards.feet_air_time.weight = 1.0 self.rewards.feet_air_time.weight = 1.0
# self.rewards.dof_torques_l2.weight = -2.0e-4
# self.rewards.dof_pos_limits.weight = -10.0
# change terrain to flat # change terrain to flat
self.scene.terrain.terrain_type = "plane" self.scene.terrain.terrain_type = "plane"
...@@ -37,14 +26,6 @@ class UnitreeA1FlatEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -37,14 +26,6 @@ class UnitreeA1FlatEnvCfg(LocomotionVelocityRoughEnvCfg):
self.observations.policy.height_scan = None self.observations.policy.height_scan = None
# no terrain curriculum # no terrain curriculum
self.curriculum.terrain_levels = None self.curriculum.terrain_levels = None
# disable pushing for now
self.randomization.push_robot = None
self.randomization.add_base_mass = None
# change body and joint names
# TODO: Change to .*foot once we make a new USD for the robot
self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*calf"
self.rewards.undesired_contacts.params["sensor_cfg"].body_names = [".*thigh", ".*hip"]
class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg): class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg):
......
...@@ -18,22 +18,40 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): ...@@ -18,22 +18,40 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
def __post_init__(self): def __post_init__(self):
# post init of parent # post init of parent
super().__post_init__() super().__post_init__()
# switch robot to unitree-a1
self.scene.robot = UNITREE_A1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.robot = UNITREE_A1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# scale down the terrains because the robot is small
self.scene.terrain.terrain_generator.sub_terrains["boxes"].grid_height_range = (0.025, 0.1)
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_range = (0.01, 0.06)
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_step = 0.01
# reduce action scale # reduce action scale
self.actions.joint_pos.scale = 0.25 self.actions.joint_pos.scale = 0.25
# override rewards
# self.rewards.dof_torques_l2.weight = -2.0e-4
# self.rewards.dof_pos_limits.weight = -10.0
# disable pushing for now # randomization
self.randomization.push_robot = None self.randomization.push_robot = None
self.randomization.add_base_mass = None self.randomization.add_base_mass = None
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": {
"x": (0.0, 0.0),
"y": (0.0, 0.0),
"z": (0.0, 0.0),
"roll": (0.0, 0.0),
"pitch": (0.0, 0.0),
"yaw": (0.0, 0.0),
},
}
# change body and joint names # rewards
# TODO: Change to .*foot once we make a new USD for the robot self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*_calf"
self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*calf" self.rewards.feet_air_time.weight = 0.01
self.rewards.undesired_contacts.params["sensor_cfg"].body_names = [".*thigh", ".*hip"] self.rewards.undesired_contacts = None
self.rewards.dof_torques_l2.weight = -0.0002
self.rewards.track_lin_vel_xy_exp.weight = 1.5
self.rewards.track_ang_vel_z_exp.weight = 0.75
self.rewards.dof_acc_l2.weight = -2.5e-7
@configclass @configclass
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment