Unverified Commit 133c61c4 authored by Brimo's avatar Brimo Committed by GitHub

Adds the Unitree G1 locomotion environment (#453)

Added Unitree G1 locomotion example

## Type of change

- New feature

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have run all the tests with `./isaaclab.sh --test` and they pass
- [ ] 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 57ca19a0
This diff is collapsed.
This diff is collapsed.
......@@ -146,6 +146,10 @@ Environments based on legged locomotion tasks.
+------------------------------+----------------------------------------------+------------------------------------------------------------------------------+
| |velocity-rough-h1| | |velocity-rough-h1-link| | Track a velocity command on rough terrain with the Unitree H1 robot |
+------------------------------+----------------------------------------------+------------------------------------------------------------------------------+
| |velocity-flat-g1| | |velocity-flat-g1-link| | Track a velocity command on flat terrain with the Unitree G1 robot |
+------------------------------+----------------------------------------------+------------------------------------------------------------------------------+
| |velocity-rough-g1| | |velocity-rough-g1-link| | Track a velocity command on rough terrain with the Unitree G1 robot |
+------------------------------+----------------------------------------------+------------------------------------------------------------------------------+
.. |velocity-flat-anymal-b-link| replace:: `Isaac-Velocity-Flat-Anymal-B-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/anymal_b/flat_env_cfg.py>`__
.. |velocity-rough-anymal-b-link| replace:: `Isaac-Velocity-Rough-Anymal-B-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py>`__
......@@ -173,6 +177,9 @@ Environments based on legged locomotion tasks.
.. |velocity-flat-h1-link| replace:: `Isaac-Velocity-Flat-H1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/h1/flat_env_cfg.py>`__
.. |velocity-rough-h1-link| replace:: `Isaac-Velocity-Rough-H1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py>`__
.. |velocity-flat-g1-link| replace:: `Isaac-Velocity-Flat-G1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py>`__
.. |velocity-rough-g1-link| replace:: `Isaac-Velocity-Rough-G1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py>`__
.. |velocity-flat-anymal-b| image:: ../_static/tasks/locomotion/anymal_b_flat.jpg
.. |velocity-rough-anymal-b| image:: ../_static/tasks/locomotion/anymal_b_rough.jpg
......@@ -189,6 +196,8 @@ Environments based on legged locomotion tasks.
.. |velocity-flat-spot| image:: ../_static/tasks/locomotion/spot_flat.jpg
.. |velocity-flat-h1| image:: ../_static/tasks/locomotion/h1_flat.jpg
.. |velocity-rough-h1| image:: ../_static/tasks/locomotion/h1_rough.jpg
.. |velocity-flat-g1| image:: ../_static/tasks/locomotion/g1_flat.jpg
.. |velocity-rough-g1| image:: ../_static/tasks/locomotion/g1_rough.jpg
Navigation
----------
......
......@@ -11,6 +11,7 @@ The following configurations are available:
* :obj:`UNITREE_GO1_CFG`: Unitree Go1 robot with actuator net model for the legs
* :obj:`UNITREE_GO2_CFG`: Unitree Go2 robot with DC motor model for the legs
* :obj:`H1_CFG`: H1 humanoid robot
* :obj:`G1_CFG`: G1 humanoid robot
Reference: https://github.com/unitreerobotics/unitree_ros
"""
......@@ -265,3 +266,121 @@ H1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1_mi
This configuration removes most collision meshes to speed up simulation.
"""
G1_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=8, solver_velocity_iteration_count=4
),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.74),
joint_pos={
".*_hip_pitch_joint": -0.20,
".*_knee_joint": 0.42,
".*_ankle_pitch_joint": -0.23,
".*_elbow_pitch_joint": 0.87,
"left_shoulder_roll_joint": 0.16,
"left_shoulder_pitch_joint": 0.35,
"right_shoulder_roll_joint": -0.16,
"right_shoulder_pitch_joint": 0.35,
"left_one_joint": 1.0,
"right_one_joint": -1.0,
"left_two_joint": 0.52,
"right_two_joint": -0.52,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
actuators={
"legs": ImplicitActuatorCfg(
joint_names_expr=[
".*_hip_yaw_joint",
".*_hip_roll_joint",
".*_hip_pitch_joint",
".*_knee_joint",
"torso_joint",
],
effort_limit=300,
velocity_limit=100.0,
stiffness={
".*_hip_yaw_joint": 150.0,
".*_hip_roll_joint": 150.0,
".*_hip_pitch_joint": 200.0,
".*_knee_joint": 200.0,
"torso_joint": 200.0,
},
damping={
".*_hip_yaw_joint": 5.0,
".*_hip_roll_joint": 5.0,
".*_hip_pitch_joint": 5.0,
".*_knee_joint": 5.0,
"torso_joint": 5.0,
},
armature={
".*_hip_.*": 0.01,
".*_knee_joint": 0.01,
"torso_joint": 0.01,
},
),
"feet": ImplicitActuatorCfg(
effort_limit=20,
joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"],
stiffness=20.0,
damping=2.0,
armature=0.01,
),
"arms": ImplicitActuatorCfg(
joint_names_expr=[
".*_shoulder_pitch_joint",
".*_shoulder_roll_joint",
".*_shoulder_yaw_joint",
".*_elbow_pitch_joint",
".*_elbow_roll_joint",
".*_five_joint",
".*_three_joint",
".*_six_joint",
".*_four_joint",
".*_zero_joint",
".*_one_joint",
".*_two_joint",
],
effort_limit=300,
velocity_limit=100.0,
stiffness=40.0,
damping=10.0,
armature={
".*_shoulder_.*": 0.01,
".*_elbow_.*": 0.01,
".*_five_joint": 0.001,
".*_three_joint": 0.001,
".*_six_joint": 0.001,
".*_four_joint": 0.001,
".*_zero_joint": 0.001,
".*_one_joint": 0.001,
".*_two_joint": 0.001,
},
),
},
)
"""Configuration for the Unitree G1 Humanoid robot."""
G1_MINIMAL_CFG = G1_CFG.copy()
G1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1_minimal.usd"
"""Configuration for the Unitree G1 Humanoid robot with fewer collision meshes.
This configuration removes most collision meshes to speed up simulation.
"""
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import gymnasium as gym
from . import agents, flat_env_cfg, rough_env_cfg
##
# Register Gym environments.
##
gym.register(
id="Isaac-Velocity-Rough-G1-v0",
entry_point="omni.isaac.lab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": rough_env_cfg.G1RoughEnvCfg,
"rsl_rl_cfg_entry_point": agents.rsl_rl_cfg.G1RoughPPORunnerCfg,
},
)
gym.register(
id="Isaac-Velocity-Rough-G1-Play-v0",
entry_point="omni.isaac.lab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": rough_env_cfg.G1RoughEnvCfg_PLAY,
"rsl_rl_cfg_entry_point": agents.rsl_rl_cfg.G1RoughPPORunnerCfg,
},
)
gym.register(
id="Isaac-Velocity-Flat-G1-v0",
entry_point="omni.isaac.lab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": flat_env_cfg.G1FlatEnvCfg,
"rsl_rl_cfg_entry_point": agents.rsl_rl_cfg.G1FlatPPORunnerCfg,
},
)
gym.register(
id="Isaac-Velocity-Flat-G1-Play-v0",
entry_point="omni.isaac.lab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": flat_env_cfg.G1FlatEnvCfg_PLAY,
"rsl_rl_cfg_entry_point": agents.rsl_rl_cfg.G1FlatPPORunnerCfg,
},
)
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from . import rsl_rl_cfg # noqa: F401, F403
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.lab.utils import configclass
from omni.isaac.lab_tasks.utils.wrappers.rsl_rl import (
RslRlOnPolicyRunnerCfg,
RslRlPpoActorCriticCfg,
RslRlPpoAlgorithmCfg,
)
@configclass
class G1RoughPPORunnerCfg(RslRlOnPolicyRunnerCfg):
num_steps_per_env = 24
max_iterations = 3000
save_interval = 50
experiment_name = "g1_rough"
empirical_normalization = False
policy = RslRlPpoActorCriticCfg(
init_noise_std=1.0,
actor_hidden_dims=[512, 256, 128],
critic_hidden_dims=[512, 256, 128],
activation="elu",
)
algorithm = RslRlPpoAlgorithmCfg(
value_loss_coef=1.0,
use_clipped_value_loss=True,
clip_param=0.2,
entropy_coef=0.008,
num_learning_epochs=5,
num_mini_batches=4,
learning_rate=1.0e-3,
schedule="adaptive",
gamma=0.99,
lam=0.95,
desired_kl=0.01,
max_grad_norm=1.0,
)
@configclass
class G1FlatPPORunnerCfg(G1RoughPPORunnerCfg):
def __post_init__(self):
super().__post_init__()
self.max_iterations = 1500
self.experiment_name = "g1_flat"
self.policy.actor_hidden_dims = [256, 128, 128]
self.policy.critic_hidden_dims = [256, 128, 128]
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.utils import configclass
from .rough_env_cfg import G1RoughEnvCfg
@configclass
class G1FlatEnvCfg(G1RoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# change terrain to flat
self.scene.terrain.terrain_type = "plane"
self.scene.terrain.terrain_generator = None
# no height scan
self.scene.height_scanner = None
self.observations.policy.height_scan = None
# no terrain curriculum
self.curriculum.terrain_levels = None
# Rewards
self.rewards.track_ang_vel_z_exp.weight = 1.0
self.rewards.lin_vel_z_l2.weight = -0.2
self.rewards.action_rate_l2.weight = -0.005
self.rewards.dof_acc_l2.weight = -1.0e-7
self.rewards.feet_air_time.weight = 0.75
self.rewards.feet_air_time.params["threshold"] = 0.4
self.rewards.dof_torques_l2.weight = -2.0e-6
self.rewards.dof_torques_l2.params["asset_cfg"] = SceneEntityCfg(
"robot", joint_names=[".*_hip_.*", ".*_knee_joint"]
)
# Commands
self.commands.base_velocity.ranges.lin_vel_x = (0.0, 1.0)
self.commands.base_velocity.ranges.lin_vel_y = (-0.5, 0.5)
self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
class G1FlatEnvCfg_PLAY(G1FlatEnvCfg):
def __post_init__(self) -> None:
# post init of parent
super().__post_init__()
# make a smaller scene for play
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
# disable randomization for play
self.observations.policy.enable_corruption = False
# remove random pushing
self.events.base_external_force_torque = None
self.events.push_robot = None
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.lab.managers import RewardTermCfg as RewTerm
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.managers import TerminationTermCfg as DoneTerm
from omni.isaac.lab.utils import configclass
import omni.isaac.lab_tasks.manager_based.locomotion.velocity.mdp as mdp
from omni.isaac.lab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
LocomotionVelocityRoughEnvCfg,
RewardsCfg,
)
##
# Pre-defined configs
##
from omni.isaac.lab_assets import G1_MINIMAL_CFG # isort: skip
@configclass
class G1Rewards(RewardsCfg):
termination_penalty = RewTerm(func=mdp.is_terminated, weight=-200.0)
track_lin_vel_xy_exp = RewTerm(
func=mdp.track_lin_vel_xy_yaw_frame_exp,
weight=1.0,
params={"command_name": "base_velocity", "std": 0.5},
)
track_ang_vel_z_exp = RewTerm(
func=mdp.track_ang_vel_z_world_exp, weight=2.0, params={"command_name": "base_velocity", "std": 0.5}
)
feet_air_time = RewTerm(
func=mdp.feet_air_time_positive_biped,
weight=0.25,
params={
"command_name": "base_velocity",
"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*_ankle_roll_link"),
"threshold": 0.4,
},
)
feet_slide = RewTerm(
func=mdp.feet_slide,
weight=-0.1,
params={
"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*_ankle_roll_link"),
"asset_cfg": SceneEntityCfg("robot", body_names=".*_ankle_roll_link"),
},
)
# Penalize ankle joint limits
dof_pos_limits = RewTerm(
func=mdp.joint_pos_limits,
weight=-1.0,
params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"])},
)
# Penalize deviation from default of the joints that are not essential for locomotion
joint_deviation_hip = RewTerm(
func=mdp.joint_deviation_l1,
weight=-0.1,
params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_hip_yaw_joint", ".*_hip_roll_joint"])},
)
joint_deviation_arms = RewTerm(
func=mdp.joint_deviation_l1,
weight=-0.1,
params={
"asset_cfg": SceneEntityCfg(
"robot",
joint_names=[
".*_shoulder_pitch_joint",
".*_shoulder_roll_joint",
".*_shoulder_yaw_joint",
".*_elbow_pitch_joint",
".*_elbow_roll_joint",
],
)
},
)
joint_deviation_fingers = RewTerm(
func=mdp.joint_deviation_l1,
weight=-0.05,
params={
"asset_cfg": SceneEntityCfg(
"robot",
joint_names=[
".*_five_joint",
".*_three_joint",
".*_six_joint",
".*_four_joint",
".*_zero_joint",
".*_one_joint",
".*_two_joint",
],
)
},
)
joint_deviation_torso = RewTerm(
func=mdp.joint_deviation_l1,
weight=-0.1,
params={"asset_cfg": SceneEntityCfg("robot", joint_names="torso_joint")},
)
@configclass
class TerminationsCfg:
"""Termination terms for the MDP."""
time_out = DoneTerm(func=mdp.time_out, time_out=True)
base_contact = DoneTerm(
func=mdp.illegal_contact,
params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names="torso_link"), "threshold": 1.0},
)
@configclass
class G1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
rewards: G1Rewards = G1Rewards()
terminations: TerminationsCfg = TerminationsCfg()
def __post_init__(self):
# post init of parent
super().__post_init__()
# Scene
self.scene.robot = G1_MINIMAL_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link"
# Randomization
self.events.push_robot = None
self.events.add_base_mass = None
self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.events.base_external_force_torque.params["asset_cfg"].body_names = ["torso_link"]
self.events.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),
},
}
# Rewards
self.rewards.lin_vel_z_l2.weight = 0.0
self.rewards.undesired_contacts = None
self.rewards.flat_orientation_l2.weight = -1.0
self.rewards.action_rate_l2.weight = -0.005
self.rewards.dof_acc_l2.weight = -1.25e-7
self.rewards.dof_acc_l2.params["asset_cfg"] = SceneEntityCfg(
"robot", joint_names=[".*_hip_.*", ".*_knee_joint"]
)
self.rewards.dof_torques_l2.weight = -1.5e-7
self.rewards.dof_torques_l2.params["asset_cfg"] = SceneEntityCfg(
"robot", joint_names=[".*_hip_.*", ".*_knee_joint", ".*_ankle_.*"]
)
# Commands
self.commands.base_velocity.ranges.lin_vel_x = (0.0, 1.0)
self.commands.base_velocity.ranges.lin_vel_y = (-0.0, 0.0)
self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
@configclass
class G1RoughEnvCfg_PLAY(G1RoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# make a smaller scene for play
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
self.episode_length_s = 40.0
# spawn the robot randomly in the grid (instead of their terrain levels)
self.scene.terrain.max_init_terrain_level = None
# reduce the number of terrains to save memory
if self.scene.terrain.terrain_generator is not None:
self.scene.terrain.terrain_generator.num_rows = 5
self.scene.terrain.terrain_generator.num_cols = 5
self.scene.terrain.terrain_generator.curriculum = False
self.commands.base_velocity.ranges.lin_vel_x = (1.0, 1.0)
self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
self.commands.base_velocity.ranges.heading = (0.0, 0.0)
# disable randomization for play
self.observations.policy.enable_corruption = False
# remove random pushing
self.events.base_external_force_torque = None
self.events.push_robot = None
......@@ -37,6 +37,7 @@ from omni.isaac.lab.sim import SimulationContext
##
from omni.isaac.lab_assets.cassie import CASSIE_CFG # isort:skip
from omni.isaac.lab_assets import H1_CFG # isort:skip
from omni.isaac.lab_assets import G1_CFG # isort:skip
def main():
......@@ -60,11 +61,13 @@ def main():
origins = torch.tensor([
[0.0, 0.0, 0.0],
[0.0, 1.0, 0.0],
[0.0, 2.0, 0.0],
])
# Robots
cassie = Articulation(CASSIE_CFG.replace(prim_path="/World/Cassie"))
h1 = Articulation(H1_CFG.replace(prim_path="/World/H1"))
robots = [cassie, h1]
g1 = Articulation(G1_CFG.replace(prim_path="/World/G1"))
robots = [cassie, h1, g1]
# Play the simulator
sim.reset()
......
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