diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 2f6eefbfb1b..e58c988c35f 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -16,6 +16,7 @@ Guidelines for modifications: * ETH Zurich * NVIDIA Corporation & Affiliates * University of Toronto +* Persona AI, Inc. --- diff --git a/docs/source/_static/tasks/locomotion/valkyrie_flat.jpg b/docs/source/_static/tasks/locomotion/valkyrie_flat.jpg new file mode 100644 index 00000000000..17df922d27d Binary files /dev/null and b/docs/source/_static/tasks/locomotion/valkyrie_flat.jpg differ diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index db74162a354..6422d13b8cc 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -288,6 +288,8 @@ Environments based on legged locomotion tasks. +------------------------------+----------------------------------------------+------------------------------------------------------------------------------+ | |velocity-rough-g1| | |velocity-rough-g1-link| | Track a velocity command on rough terrain with the Unitree G1 robot | +------------------------------+----------------------------------------------+------------------------------------------------------------------------------+ + | |velocity-flat-valkyrie| | |velocity-flat-valkyrie-link| | Track a velocity command on flat terrain with the Valkyrie 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 `__ @@ -318,6 +320,8 @@ Environments based on legged locomotion tasks. .. |velocity-flat-g1-link| replace:: `Isaac-Velocity-Flat-G1-v0 `__ .. |velocity-rough-g1-link| replace:: `Isaac-Velocity-Rough-G1-v0 `__ +.. |velocity-flat-valkyrie-link| replace:: `Isaac-Velocity-Flat-Valkyrie-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 @@ -336,6 +340,7 @@ Environments based on legged locomotion tasks. .. |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 +.. |velocity-flat-valkyrie| image:: ../_static/tasks/locomotion/valkyrie_flat.jpg Navigation ~~~~~~~~~~ diff --git a/source/isaaclab_assets/isaaclab_assets/robots/__init__.py b/source/isaaclab_assets/isaaclab_assets/robots/__init__.py index a4515156081..135705d6f5e 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/__init__.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/__init__.py @@ -24,3 +24,4 @@ from .spot import * from .unitree import * from .universal_robots import * +from .valkyrie import * diff --git a/source/isaaclab_assets/isaaclab_assets/robots/valkyrie.py b/source/isaaclab_assets/isaaclab_assets/robots/valkyrie.py new file mode 100644 index 00000000000..05a7c79a0d6 --- /dev/null +++ b/source/isaaclab_assets/isaaclab_assets/robots/valkyrie.py @@ -0,0 +1,116 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +Configuration for the Valkyrie robot from IHMC Robotics. +""" + +import isaaclab.sim as sim_utils +from isaaclab.actuators import ImplicitActuatorCfg +from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR + +spawn_usd = sim_utils.UsdFileCfg( + usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Valkyrie/valkyrie.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 + ), +) + +VALKYRIE_CFG = ArticulationCfg( + spawn=spawn_usd, + init_state=ArticulationCfg.InitialStateCfg( + pos=(0.0, 0.0, 1.2), + joint_pos={ + ".*HipPitch": -0.20, + ".*KneePitch": 0.42, + ".*AnklePitch": -0.23, + "leftShoulderPitch": 0.27, + "rightShoulderPitch": 0.27, + "leftElbowPitch": -0.7, + "rightElbowPitch": 0.7, + "leftShoulderRoll": -1.2, + "rightShoulderRoll": 1.2, + }, + joint_vel={".*": 0.0}, + ), + soft_joint_pos_limit_factor=0.9, + actuators={ + "torso": ImplicitActuatorCfg( + effort_limit=2000, + joint_names_expr=["torso.*"], + stiffness={ + "torsoPitch": 150.0, + "torsoRoll": 150.0, + "torsoYaw": 150.0, + }, + damping={ + "torsoPitch": 5.0, + "torsoRoll": 5.0, + "torsoYaw": 5.0, + }, + armature=0.01, + ), + "legs": ImplicitActuatorCfg( + joint_names_expr=[ + ".*HipYaw", + ".*HipRoll", + ".*HipPitch", + ".*Knee.*", + ], + effort_limit=300, + velocity_limit=100.0, + stiffness={ + ".*HipYaw": 150.0, + ".*HipRoll": 150.0, + ".*HipPitch": 200.0, + ".*Knee.*": 200.0, + }, + damping={ + ".*HipYaw": 5.0, + ".*HipRoll": 5.0, + ".*HipPitch": 5.0, + ".*Knee.*": 5.0, + }, + armature={ + ".*Hip.*": 0.01, + ".*Knee.*": 0.01, + }, + ), + "feet": ImplicitActuatorCfg( + effort_limit=20, + joint_names_expr=[".*AnklePitch", ".*AnkleRoll"], + stiffness=20.0, + damping=2.0, + armature=0.01, + ), + "arms": ImplicitActuatorCfg( + joint_names_expr=[ + ".*Shoulder.*", + ".*Elbow.*", + ".*Forearm.*", + ], + effort_limit=300, + velocity_limit=100.0, + stiffness=40.0, + damping=10.0, + armature={ + ".*Shoulder.*": 0.01, + ".*Elbow.*": 0.01, + ".*Forearm.*": 0.001, + }, + ), + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py index 54620f98435..4ea67a8b3a4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py @@ -47,7 +47,7 @@ class G1Rewards(RewardsCfg): }, ) - # Penalize ankle joint limits + # PenalizIsaac-Velocity-Flat-Valkyrie-v0e ankle joint limits dof_pos_limits = RewTerm( func=mdp.joint_pos_limits, weight=-1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/__init__.py new file mode 100644 index 00000000000..eaf2ff61d0e --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/__init__.py @@ -0,0 +1,35 @@ +# Copyright (c) 2022-2025, 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-Flat-Valkyrie-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": flat_env_cfg.ValkyrieFlatEnvCfg, + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ValkyrieFlatPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", + }, +) + + +gym.register( + id="Isaac-Velocity-Flat-Valkyrie-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": flat_env_cfg.ValkyrieFlatEnvCfg_PLAY, + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ValkyrieFlatPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/__init__.py new file mode 100644 index 00000000000..e75ca2bc3f9 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/skrl_flat_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/skrl_flat_ppo_cfg.yaml new file mode 100644 index 00000000000..8d544a32b5f --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/agents/skrl_flat_ppo_cfg.yaml @@ -0,0 +1,82 @@ +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: # see gaussian_model parameters + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: net + input: STATES + layers: [256, 128, 128] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [256, 128, 128] + activations: elu + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + # The agent collects number of environment steps during each episode. + # The collected data is then divided into and used for optimization epochs. + rollouts: 24 # number of steps to take in each rollout + learning_epochs: 5 # + mini_batches: 4 # number of mini baches + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 1.0e-03 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.01 + state_preprocessor: null + state_preprocessor_kwargs: null + value_preprocessor: null + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 # clipping coefficient for computing the clipped surrogate objective + value_clip: 0.2 # clipping coefficient for computing the value loss (if clip_predicted_values is True) + clip_predicted_values: True # clip predicted values during value loss computation + entropy_loss_scale: 0.008 # 0.008 # the bigger, the more exploratin + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 1.0 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "valk_flat" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 36000 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/flat_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/flat_env_cfg.py new file mode 100644 index 00000000000..5a9e34c2166 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/flat_env_cfg.py @@ -0,0 +1,87 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.managers import SceneEntityCfg +from isaaclab.utils import configclass + +from .rough_env_cfg import ValkyrieRoughEnvCfg + + +@configclass +class ValkyrieFlatEnvCfg(ValkyrieRoughEnvCfg): + 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_lin_vel_xy_exp.weight = 2.0 + self.rewards.track_ang_vel_z_exp.weight = 1.0 + self.rewards.flat_orientation_l2.weight = -1.0 + + self.rewards.lin_vel_z_l2.weight = -0.2 + self.rewards.action_rate_l2.weight = -0.005 + + self.rewards.feet_air_time.weight = 2.5 + self.rewards.feet_air_time.params["threshold"] = 0.4 + + # penalize joint limit if they cross soft limit + self.rewards.feet_pos_limits.weight = -1.0 + self.rewards.torso_roll_pos_limits.weight = -1.0 + + self.rewards.joint_deviation_hip.weight = -0.4 + self.rewards.joint_deviation_feet.weight = -0.4 + self.rewards.joint_deviation_arms.weight = -1.0 + self.rewards.joint_deviation_torso.weight = -1.0 + self.rewards.joint_deviation_torso_roll.weight = -1.0 + + self.rewards.feet_slide.weight = -0.1 + + self.rewards.dof_acc_l2.weight = -1.25e-7 + self.rewards.dof_acc_l2.params["asset_cfg"] = SceneEntityCfg("robot", joint_names=[".*Hip.*", ".*Knee.*"]) + self.rewards.dof_torques_l2.weight = -1.5e-7 + self.rewards.dof_torques_l2.params["asset_cfg"] = SceneEntityCfg("robot", joint_names=[".*Hip.*", ".*Knee.*"]) + # 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 ValkyrieFlatEnvCfg_PLAY(ValkyrieFlatEnvCfg): + 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 + + 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 = (0.0, 0.0) + self.events.reset_base.params = { + "pose_range": {"x": (0, 0), "y": (0, 0), "yaw": (0, 0)}, + "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), + }, + } diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/rough_env_cfg.py new file mode 100644 index 00000000000..df703b519cd --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/valkyrie/rough_env_cfg.py @@ -0,0 +1,172 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +## +# Pre-defined configs +## +from isaaclab_assets import VALKYRIE_CFG + +from isaaclab.managers import RewardTermCfg as RewTerm +from isaaclab.managers import SceneEntityCfg +from isaaclab.utils import configclass + +import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp +from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg, RewardsCfg + + +@configclass +class ValkyrieRewards(RewardsCfg): + """Reward terms for the MDP.""" + + 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.6, + params={ + "command_name": "base_velocity", + "sensor_cfg": SceneEntityCfg("contact_forces", body_names=["leftFoot", "rightFoot"]), + "threshold": 0.4, + }, + ) + feet_slide = RewTerm( + func=mdp.feet_slide, + weight=-0.1, + params={ + "sensor_cfg": SceneEntityCfg("contact_forces", body_names=["leftFoot", "rightFoot"]), + "asset_cfg": SceneEntityCfg("robot", body_names=["leftFoot", "rightFoot"]), + }, + ) + + # Penalize ankle joint limits + feet_pos_limits = RewTerm( + func=mdp.joint_pos_limits, + weight=-1.0, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*AnklePitch"])}, + ) + torso_roll_pos_limits = RewTerm( + func=mdp.joint_pos_limits, + weight=-1.0, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["torsoRoll"])}, + ) + # Penalize deviation from default of the joints that are not essential for locomotion + joint_deviation_feet = RewTerm( + func=mdp.joint_deviation_l1, + weight=-0.4, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*AnkleRoll"])}, + ) + joint_deviation_hip = RewTerm( + func=mdp.joint_deviation_l1, + weight=-0.1, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*HipYaw", ".*HipRoll"])}, + ) + joint_deviation_torso = RewTerm( + func=mdp.joint_deviation_l1, + weight=-0.4, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["torsoPitch", "torsoYaw"])}, + ) + joint_deviation_torso_roll = RewTerm( + func=mdp.joint_deviation_l1, + weight=-0.4, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["torsoRoll"])}, + ) + joint_deviation_arms = RewTerm( + func=mdp.joint_deviation_l1, + weight=-0.1, + params={ + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + ".*Shoulder.*", + ".*ElbowPitch", + ], + ) + }, + ) + + +@configclass +class ValkyrieRoughEnvCfg(LocomotionVelocityRoughEnvCfg): + rewards: ValkyrieRewards = ValkyrieRewards() + + def __post_init__(self): + # post init of parent + super().__post_init__() + # Scene + self.scene.robot = VALKYRIE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torsoYawLink" + + # 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 = ["torsoYawLink"] + 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.*"]) + self.rewards.dof_torques_l2.weight = -1.5e-7 + self.rewards.dof_torques_l2.params["asset_cfg"] = SceneEntityCfg( + "robot", joint_names=[".*Hip.*", ".*Knee.*", ".*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) + + # terminations + self.terminations.base_contact.params["sensor_cfg"].body_names = ["torso.*", ".*Hip.*"] + + +@configclass +class ValkyrieRoughEnvCfg_PLAY(ValkyrieRoughEnvCfg): + 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