diff --git a/docs/source/_static/tasks/locomotion/g1_flat.jpg b/docs/source/_static/tasks/locomotion/g1_flat.jpg new file mode 100644 index 0000000000..cf9e1b1482 Binary files /dev/null and b/docs/source/_static/tasks/locomotion/g1_flat.jpg differ diff --git a/docs/source/_static/tasks/locomotion/g1_rough.jpg b/docs/source/_static/tasks/locomotion/g1_rough.jpg new file mode 100644 index 0000000000..25ed68d6e1 Binary files /dev/null and b/docs/source/_static/tasks/locomotion/g1_rough.jpg differ diff --git a/docs/source/api/lab/omni.isaac.lab.app.rst b/docs/source/api/lab/omni.isaac.lab.app.rst index 03c69bf12c..5616fa74ec 100644 --- a/docs/source/api/lab/omni.isaac.lab.app.rst +++ b/docs/source/api/lab/omni.isaac.lab.app.rst @@ -28,6 +28,12 @@ The following details the behavior of the class based on the environment variabl * ``LIVESTREAM=2`` enables streaming via the `WebRTC Livestream`_ extension. This allows users to connect in a browser using the WebRTC protocol. + .. note:: + + Each Isaac Sim instance can only connect to one streaming client. + Connecting to an Isaac Sim instance that is currently serving a streaming client + results in an error for the second user. + * **Enable cameras**: If the environment variable ``ENABLE_CAMERAS`` is set to 1, then the cameras are enabled. This is useful for running the simulator without a GUI but still rendering the viewport and camera images. diff --git a/docs/source/features/actuators.rst b/docs/source/features/actuators.rst index c84e4c6b03..c22b79a757 100644 --- a/docs/source/features/actuators.rst +++ b/docs/source/features/actuators.rst @@ -47,7 +47,7 @@ Actuator groups --------------- The actuator models by themselves are computational blocks that take as inputs the desired joint commands -and output the the joint commands to apply into the simulator. They do not contain any knowledge about the +and output the joint commands to apply into the simulator. They do not contain any knowledge about the joints they are acting on themselves. These are handled by the :class:`omni.isaac.lab.assets.Articulation` class, which wraps around the physics engine's articulation class. @@ -67,4 +67,4 @@ The following figure shows the actuator groups for a legged mobile manipulator: .. seealso:: We provide implementations for various explicit actuator models. These are detailed in - `omni.isaac.lab.actuators <../api/lab.actuators.html>`_ sub-package. + `omni.isaac.lab.actuators <../api/lab/omni.isaac.lab.actuators.html>`_ sub-package. diff --git a/docs/source/features/environments.rst b/docs/source/features/environments.rst index 0c5f6a6304..e1b0c0339a 100644 --- a/docs/source/features/environments.rst +++ b/docs/source/features/environments.rst @@ -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 `__ .. |velocity-rough-anymal-b-link| replace:: `Isaac-Velocity-Rough-Anymal-B-v0 `__ @@ -173,6 +177,9 @@ Environments based on legged locomotion tasks. .. |velocity-flat-h1-link| replace:: `Isaac-Velocity-Flat-H1-v0 `__ .. |velocity-rough-h1-link| replace:: `Isaac-Velocity-Rough-H1-v0 `__ +.. |velocity-flat-g1-link| replace:: `Isaac-Velocity-Flat-G1-v0 `__ +.. |velocity-rough-g1-link| replace:: `Isaac-Velocity-Rough-G1-v0 `__ + .. |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 ---------- diff --git a/docs/source/features/tiled_rendering.rst b/docs/source/features/tiled_rendering.rst index 9ef6962b75..ac6285159a 100644 --- a/docs/source/features/tiled_rendering.rst +++ b/docs/source/features/tiled_rendering.rst @@ -11,6 +11,8 @@ Tiled Rendering This feature is only available from Isaac Sim version 4.0.0. + Tiled rendering requires heavy memory resources. We recommend running at most 256 cameras in the scene. + Tiled rendering APIs provide a vectorized interface for collecting data from camera sensors. This is useful for reinforcement learning environments requiring vision in the loop. Tiled rendering works by concatenating camera outputs from multiple cameras and rendering diff --git a/docs/source/setup/faq.rst b/docs/source/setup/faq.rst index d403215b2a..b68b5ffb9c 100644 --- a/docs/source/setup/faq.rst +++ b/docs/source/setup/faq.rst @@ -80,8 +80,8 @@ to Isaac Lab, please reach out to us. .. _PhysX: https://developer.nvidia.com/physx-sdk .. _Isaac Sim: https://developer.nvidia.com/isaac-sim .. _Isaac Gym: https://developer.nvidia.com/isaac-gym -.. _IsaacGymEnvs: https://github.com/NVIDIA-Omniverse/IsaacGymEnvs -.. _OmniIsaacGymEnvs: https://github.com/NVIDIA-Omniverse/OmniIsaacGymEnvs +.. _IsaacGymEnvs: https://github.com/isaac-sim/IsaacGymEnvs +.. _OmniIsaacGymEnvs: https://github.com/isaac-sim/OmniIsaacGymEnvs .. _Orbit: https://isaac-orbit.github.io/orbit .. _Isaac Automator: https://github.com/isaac-sim/IsaacAutomator .. _migration guides: ../migration/index.html diff --git a/docs/source/setup/installation/cloud_installation.rst b/docs/source/setup/installation/cloud_installation.rst index cf68f18131..3b1319c11d 100644 --- a/docs/source/setup/installation/cloud_installation.rst +++ b/docs/source/setup/installation/cloud_installation.rst @@ -10,6 +10,8 @@ The result is a fully configured remote desktop cloud workstation, which can be Installing Isaac Automator -------------------------- +For the most update-to-date and complete installation instructions, please refer to `Isaac Automator `__. + To use Isaac Automator, first clone the repo: .. code-block:: bash @@ -49,9 +51,31 @@ Running Isaac Automator To run Isaac Automator, first build the Isaac Automator container: -.. code-block:: bash +.. tabs:: + + .. tab:: Linux + .. code-block:: bash + + ./build + + .. tab:: Windows + .. code-block:: bash + + docker build --platform linux/x86_64 -t isa . + +Next, enter the automator container: + +.. tabs:: + + .. tab:: Linux + .. code-block:: bash + + ./run + + .. tab:: Windows + .. code-block:: bash - ./build + docker run --platform linux/x86_64 -it --rm -v .:/app isa bash Next, run the deployed script for your preferred cloud: diff --git a/docs/source/setup/sample.rst b/docs/source/setup/sample.rst index 19c721c188..48db4b5d7e 100644 --- a/docs/source/setup/sample.rst +++ b/docs/source/setup/sample.rst @@ -215,7 +215,7 @@ from the environments into the respective libraries function argument and return # run script for training ./isaaclab.sh -p source/standalone/workflows/rsl_rl/train.py --task Isaac-Reach-Franka-v0 --headless # run script for playing with 32 environments - ./isaaclab.sh -p source/standalone/workflows/rsl_rl/play.py --task Isaac-Reach-Franka-v0 --num_envs 32 --checkpoint /PATH/TO/model.pth + ./isaaclab.sh -p source/standalone/workflows/rsl_rl/play.py --task Isaac-Reach-Franka-v0 --num_envs 32 --load_run run_folder_name --checkpoint model.pt All the scripts above log the training progress to `Tensorboard`_ in the ``logs`` directory in the root of the repository. The logs directory follows the pattern ``logs///``, where ```` diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation.py index 65ea74ad0b..0fbbbabb76 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation.py @@ -345,7 +345,7 @@ def write_joint_state_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_pos[env_ids, joint_ids] = position @@ -377,7 +377,7 @@ def write_joint_stiffness_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_stiffness[env_ids, joint_ids] = stiffness @@ -407,7 +407,7 @@ def write_joint_damping_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_damping[env_ids, joint_ids] = damping @@ -435,7 +435,7 @@ def write_joint_effort_limit_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # move tensor to cpu if needed if isinstance(limits, torch.Tensor): @@ -466,7 +466,7 @@ def write_joint_armature_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_armature[env_ids, joint_ids] = armature @@ -493,7 +493,7 @@ def write_joint_friction_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_friction[env_ids, joint_ids] = joint_friction @@ -521,7 +521,7 @@ def write_joint_limits_to_sim( physx_env_ids = self._ALL_INDICES if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set into internal buffers self._data.joint_limits[env_ids, joint_ids] = limits @@ -551,7 +551,7 @@ def set_joint_position_target( env_ids = slice(None) if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set targets self._data.joint_pos_target[env_ids, joint_ids] = target @@ -575,7 +575,7 @@ def set_joint_velocity_target( env_ids = slice(None) if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set targets self._data.joint_vel_target[env_ids, joint_ids] = target @@ -599,7 +599,7 @@ def set_joint_effort_target( env_ids = slice(None) if joint_ids is None: joint_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and joint_ids != slice(None): env_ids = env_ids[:, None] # set targets self._data.joint_effort_target[env_ids, joint_ids] = target @@ -626,7 +626,7 @@ def set_fixed_tendon_stiffness( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set stiffness self._data.fixed_tendon_stiffness[env_ids, fixed_tendon_ids] = stiffness @@ -653,7 +653,7 @@ def set_fixed_tendon_damping( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set damping self._data.fixed_tendon_damping[env_ids, fixed_tendon_ids] = damping @@ -680,7 +680,7 @@ def set_fixed_tendon_limit_stiffness( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set limit_stiffness self._data.fixed_tendon_limit_stiffness[env_ids, fixed_tendon_ids] = limit_stiffness @@ -707,7 +707,7 @@ def set_fixed_tendon_limit( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set limit self._data.fixed_tendon_limit[env_ids, fixed_tendon_ids] = limit @@ -734,7 +734,7 @@ def set_fixed_tendon_rest_length( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set rest_length self._data.fixed_tendon_rest_length[env_ids, fixed_tendon_ids] = rest_length @@ -761,7 +761,7 @@ def set_fixed_tendon_offset( env_ids = slice(None) if fixed_tendon_ids is None: fixed_tendon_ids = slice(None) - elif env_ids != slice(None): + if env_ids != slice(None) and fixed_tendon_ids != slice(None): env_ids = env_ids[:, None] # set offset self._data.fixed_tendon_offset[env_ids, fixed_tendon_ids] = offset diff --git a/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py b/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py index 8533010a84..e13722ae59 100644 --- a/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py +++ b/source/extensions/omni.isaac.lab_assets/omni/isaac/lab_assets/unitree.py @@ -11,6 +11,7 @@ * :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 @@ 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. +""" diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/__init__.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/__init__.py new file mode 100644 index 0000000000..86a136395d --- /dev/null +++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/__init__.py @@ -0,0 +1,56 @@ +# 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, + }, +) diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/__init__.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/__init__.py new file mode 100644 index 0000000000..b3a5a970d3 --- /dev/null +++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/__init__.py @@ -0,0 +1,6 @@ +# 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 diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/rsl_rl_cfg.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/rsl_rl_cfg.py new file mode 100644 index 0000000000..2e7a71b95d --- /dev/null +++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/agents/rsl_rl_cfg.py @@ -0,0 +1,52 @@ +# 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] diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py new file mode 100644 index 0000000000..81eb591f12 --- /dev/null +++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py @@ -0,0 +1,56 @@ +# 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 diff --git a/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py new file mode 100644 index 0000000000..554e6bd9d1 --- /dev/null +++ b/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py @@ -0,0 +1,191 @@ +# 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 diff --git a/source/standalone/demos/bipeds.py b/source/standalone/demos/bipeds.py index 773589904e..66cb2a051a 100644 --- a/source/standalone/demos/bipeds.py +++ b/source/standalone/demos/bipeds.py @@ -37,6 +37,7 @@ ## 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()