diff --git a/source/ext_template/ext_template/assets/__init__.py b/source/ext_template/ext_template/assets/__init__.py new file mode 100644 index 00000000..53f31bc1 --- /dev/null +++ b/source/ext_template/ext_template/assets/__init__.py @@ -0,0 +1,5 @@ +""" +Python module serving as a project/extension template. +""" + +from .assets import * \ No newline at end of file diff --git a/source/ext_template/ext_template/assets/assets/__init__.py b/source/ext_template/ext_template/assets/assets/__init__.py new file mode 100644 index 00000000..1d9bef01 --- /dev/null +++ b/source/ext_template/ext_template/assets/assets/__init__.py @@ -0,0 +1,23 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Package containing asset and sensor configurations.""" + +import os +import toml + +# Conveniences to other module directories via relative paths +ISAACLAB_ASSETS_EXT_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), "../")) +"""Path to the extension source directory.""" + +ISAACLAB_ASSETS_DATA_DIR = os.path.join(ISAACLAB_ASSETS_EXT_DIR, "data") +"""Path to the extension data directory.""" + +## +# Configuration for different assets. +## + +from .anymal import * +from .velodyne import * \ No newline at end of file diff --git a/source/ext_template/ext_template/assets/assets/anymal.py b/source/ext_template/ext_template/assets/assets/anymal.py new file mode 100644 index 00000000..24d694fa --- /dev/null +++ b/source/ext_template/ext_template/assets/assets/anymal.py @@ -0,0 +1,103 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for the ANYbotics robots. + +The following configuration parameters are available: + +* :obj:`ANYMAL_B_CFG`: The ANYmal-B robot with ANYdrives 3.0 +* :obj:`ANYMAL_C_CFG`: The ANYmal-C robot with ANYdrives 3.0 +* :obj:`ANYMAL_D_CFG`: The ANYmal-D robot with ANYdrives 3.0 + +Reference: + +* https://github.com/ANYbotics/anymal_b_simple_description +* https://github.com/ANYbotics/anymal_c_simple_description +* https://github.com/ANYbotics/anymal_d_simple_description + +""" + +import isaaclab.sim as sim_utils +from isaaclab.actuators import ActuatorNetLSTMCfg, DCMotorCfg +from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.sensors import RayCasterCfg +# from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR +from . import ISAACLAB_ASSETS_DATA_DIR + +from .velodyne import VELODYNE_VLP_16_RAYCASTER_CFG + +## +# Configuration - Actuators. +## + +ANYDRIVE_3_SIMPLE_ACTUATOR_CFG = DCMotorCfg( + joint_names_expr=[".*HAA", ".*HFE", ".*KFE"], + saturation_effort=120.0, + effort_limit=80.0, + velocity_limit=7.5, + stiffness={".*": 40.0}, + damping={".*": 5.0}, +) +"""Configuration for ANYdrive 3.x with DC actuator model.""" + + +ANYDRIVE_3_LSTM_ACTUATOR_CFG = ActuatorNetLSTMCfg( + joint_names_expr=[".*HAA", ".*HFE", ".*KFE"], + network_file=f"{ISAACLAB_ASSETS_DATA_DIR}/ActuatorNets/ANYbotics/anydrive_3_lstm_jit.pt", + saturation_effort=120.0, + effort_limit=80.0, + velocity_limit=7.5, +) +"""Configuration for ANYdrive 3.0 (used on ANYmal-C) with LSTM actuator model.""" + + +ANYMAL_C_CFG = ArticulationCfg( + spawn=sim_utils.UsdFileCfg( + usd_path=f"{ISAACLAB_ASSETS_DATA_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd", + # usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.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=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 + ), + # collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.02, rest_offset=0.0), + ), + init_state=ArticulationCfg.InitialStateCfg( + pos=(0.0, 0.0, 0.6), + joint_pos={ + ".*HAA": 0.0, # all HAA + ".*F_HFE": 0.4, # both front HFE + ".*H_HFE": -0.4, # both hind HFE + ".*F_KFE": -0.8, # both front KFE + ".*H_KFE": 0.8, # both hind KFE + }, + ), + actuators={"legs": ANYDRIVE_3_LSTM_ACTUATOR_CFG}, + soft_joint_pos_limit_factor=0.95, +) +"""Configuration of ANYmal-D robot using actuator-net. + +Note: + Since we don't have a publicly available actuator network for ANYmal-D, we use the same network as ANYmal-C. + This may impact the sim-to-real transfer performance. +""" + + +## +# Configuration - Sensors. +## + +ANYMAL_LIDAR_CFG = VELODYNE_VLP_16_RAYCASTER_CFG.replace( + offset=RayCasterCfg.OffsetCfg(pos=(-0.310, 0.000, 0.159), rot=(0.0, 0.0, 0.0, 1.0)) +) +"""Configuration for the Velodyne VLP-16 sensor mounted on the ANYmal robot's base.""" diff --git a/source/ext_template/ext_template/assets/assets/velodyne.py b/source/ext_template/ext_template/assets/assets/velodyne.py new file mode 100644 index 00000000..d2324e11 --- /dev/null +++ b/source/ext_template/ext_template/assets/assets/velodyne.py @@ -0,0 +1,26 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Velodyne LiDAR sensors.""" + + +from isaaclab.sensors import RayCasterCfg, patterns + +## +# Configuration +## + +VELODYNE_VLP_16_RAYCASTER_CFG = RayCasterCfg( + attach_yaw_only=False, + pattern_cfg=patterns.LidarPatternCfg( + channels=16, vertical_fov_range=(-15.0, 15.0), horizontal_fov_range=(-180.0, 180.0), horizontal_res=0.2 + ), + debug_vis=True, + max_distance=100, +) +"""Configuration for Velodyne Puck LiDAR (VLP-16) as a :class:`RayCasterCfg`. + +Reference: https://velodynelidar.com/wp-content/uploads/2019/12/63-9229_Rev-K_Puck-_Datasheet_Web.pdf +""" diff --git a/source/ext_template/ext_template/assets/data/ActuatorNets/ANYbotics/anydrive_3_lstm_jit.pt b/source/ext_template/ext_template/assets/data/ActuatorNets/ANYbotics/anydrive_3_lstm_jit.pt new file mode 100644 index 00000000..7e9be748 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/ActuatorNets/ANYbotics/anydrive_3_lstm_jit.pt differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/instanceable_meshes.usd b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/instanceable_meshes.usd new file mode 100644 index 00000000..be52be5b Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/instanceable_meshes.usd differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/base.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/base.jpg new file mode 100644 index 00000000..8af8bc33 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/base.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/battery.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/battery.jpg new file mode 100644 index 00000000..1b6c624b Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/battery.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/bottom_shell.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/bottom_shell.jpg new file mode 100644 index 00000000..f17922b6 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/bottom_shell.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/depth_camera.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/depth_camera.jpg new file mode 100644 index 00000000..a7f1163a Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/depth_camera.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/drive.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/drive.jpg new file mode 100644 index 00000000..9570bc00 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/drive.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/face.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/face.jpg new file mode 100644 index 00000000..571c2ef7 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/face.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/foot.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/foot.jpg new file mode 100644 index 00000000..a66ea590 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/foot.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/handle.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/handle.jpg new file mode 100644 index 00000000..0300039b Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/handle.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hatch.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hatch.jpg new file mode 100644 index 00000000..b4043634 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hatch.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hip.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hip.jpg new file mode 100644 index 00000000..5194cf58 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/hip.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar.jpg new file mode 100644 index 00000000..01dc9203 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar_cage.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar_cage.jpg new file mode 100644 index 00000000..27ef15b2 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/lidar_cage.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/remote.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/remote.jpg new file mode 100644 index 00000000..1426eb7d Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/remote.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/shank.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/shank.jpg new file mode 100644 index 00000000..b803eaac Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/shank.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/thigh.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/thigh.jpg new file mode 100644 index 00000000..c3783c6f Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/thigh.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/top_shell.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/top_shell.jpg new file mode 100644 index 00000000..9f02cc01 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/top_shell.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/wide_angle_camera.jpg b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/wide_angle_camera.jpg new file mode 100644 index 00000000..ca8e9620 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/Props/materials/wide_angle_camera.jpg differ diff --git a/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/anymal_c.usd b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/anymal_c.usd new file mode 100644 index 00000000..00e8a826 Binary files /dev/null and b/source/ext_template/ext_template/assets/data/Robots/ANYbotics/ANYmal-C/anymal_c.usd differ diff --git a/source/ext_template/ext_template/assets/test/test_valid_configs.py b/source/ext_template/ext_template/assets/test/test_valid_configs.py new file mode 100644 index 00000000..167806d5 --- /dev/null +++ b/source/ext_template/ext_template/assets/test/test_valid_configs.py @@ -0,0 +1,70 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +# ignore private usage of variables warning +# pyright: reportPrivateUsage=none + +"""Launch Isaac Sim Simulator first.""" + +from omni.isaac.lab.app import AppLauncher, run_tests + +# launch the simulator +app_launcher = AppLauncher(headless=True) +simulation_app = app_launcher.app + + +"""Rest everything follows.""" + +import unittest + +import omni.isaac.lab_assets as lab_assets # noqa: F401 + +from omni.isaac.lab.assets import AssetBase, AssetBaseCfg +from omni.isaac.lab.sim import build_simulation_context + + +class TestValidEntitiesConfigs(unittest.TestCase): + """Test cases for all registered entities configurations.""" + + @classmethod + def setUpClass(cls): + # load all registered entities configurations from the module + cls.registered_entities: dict[str, AssetBaseCfg] = {} + # inspect all classes from the module + for obj_name in dir(lab_assets): + obj = getattr(lab_assets, obj_name) + # store all registered entities configurations + if isinstance(obj, AssetBaseCfg): + cls.registered_entities[obj_name] = obj + # print all existing entities names + print(">>> All registered entities:", list(cls.registered_entities.keys())) + + """ + Test fixtures. + """ + + def test_asset_configs(self): + """Check all registered asset configurations.""" + # iterate over all registered assets + for asset_name, entity_cfg in self.registered_entities.items(): + for device in ("cuda:0", "cpu"): + with self.subTest(asset_name=asset_name, device=device): + with build_simulation_context(device=device, auto_add_lighting=True) as sim: + # print the asset name + print(f">>> Testing entity {asset_name} on device {device}") + # name the prim path + entity_cfg.prim_path = "/World/asset" + # create the asset / sensors + entity: AssetBase = entity_cfg.class_type(entity_cfg) # type: ignore + + # play the sim + sim.reset() + + # check asset is initialized successfully + self.assertTrue(entity.is_initialized) + + +if __name__ == "__main__": + run_tests() diff --git a/source/ext_template/ext_template/tasks/direct/__init__.py b/source/ext_template/ext_template/tasks/direct/__init__.py new file mode 100644 index 00000000..4868dda8 --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/__init__.py @@ -0,0 +1,10 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +Direct workflow environments. +""" + +import gymnasium as gym \ No newline at end of file diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/__init__.py b/source/ext_template/ext_template/tasks/direct/anymal_c/__init__.py new file mode 100644 index 00000000..6ecb6b4d --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/__init__.py @@ -0,0 +1,40 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +Ant locomotion environment. +""" + +import gymnasium as gym + +from . import agents + +## +# Register Gym environments. +## + +gym.register( + id="Template-Isaac-Velocity-Flat-Anymal-C-Direct-v0", + entry_point=f"{__name__}.anymal_c_env:AnymalCEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.anymal_c_env_cfg:AnymalCFlatEnvCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_flat_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCFlatPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", + }, +) + +gym.register( + id="Template-Isaac-Velocity-Rough-Anymal-C-Direct-v0", + entry_point=f"{__name__}.anymal_c_env:AnymalCEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.anymal_c_env_cfg:AnymalCRoughEnvCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/agents/__init__.py b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/__init__.py new file mode 100644 index 00000000..e75ca2bc --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/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/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_flat_ppo_cfg.yaml b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_flat_ppo_cfg.yaml new file mode 100644 index 00000000..4bb7435f --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_flat_ppo_cfg.yaml @@ -0,0 +1,76 @@ +params: + seed: 42 + + # environment wrapper clipping + env: + clip_actions: 1.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [128, 128, 128] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False # flag which sets whether to load the checkpoint + load_path: '' # path to the checkpoint to load + + config: + name: anymal_c_flat_direct + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: True + normalize_input: False + normalize_value: True + value_bootstrap: True + num_actors: -1 # configured from the script (based on num_envs) + reward_shaper: + scale_value: 0.6 + normalize_advantage: True + gamma: 0.99 + tau: 0.95 + learning_rate: 1e-3 + lr_schedule: adaptive + schedule_type: legacy + kl_threshold: 0.01 + score_to_win: 20000 + max_epochs: 1500 + save_best_after: 100 + save_frequency: 50 + grad_norm: 1.0 + entropy_coef: 0.005 + truncate_grads: True + e_clip: 0.2 + horizon_length: 24 + minibatch_size: 24576 + mini_epochs: 5 + critic_coef: 2.0 + clip_value: True + seq_length: 4 + bounds_loss_coef: 0.0 diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_rough_ppo_cfg.yaml b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_rough_ppo_cfg.yaml new file mode 100644 index 00000000..1995015e --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rl_games_rough_ppo_cfg.yaml @@ -0,0 +1,76 @@ +params: + seed: 42 + + # environment wrapper clipping + env: + clip_actions: 1.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [512, 256, 128] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False # flag which sets whether to load the checkpoint + load_path: '' # path to the checkpoint to load + + config: + name: anymal_c_rough_direct + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: True + normalize_input: False + normalize_value: True + value_bootstrap: True + num_actors: -1 # configured from the script (based on num_envs) + reward_shaper: + scale_value: 0.6 + normalize_advantage: True + gamma: 0.99 + tau: 0.95 + learning_rate: 1e-3 + lr_schedule: adaptive + schedule_type: legacy + kl_threshold: 0.01 + score_to_win: 20000 + max_epochs: 1500 + save_best_after: 100 + save_frequency: 50 + grad_norm: 1.0 + entropy_coef: 0.005 + truncate_grads: True + e_clip: 0.2 + horizon_length: 24 + minibatch_size: 24576 + mini_epochs: 5 + critic_coef: 2.0 + clip_value: True + seq_length: 4 + bounds_loss_coef: 0.0 diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rsl_rl_ppo_cfg.py b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 00000000..ff304f43 --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,70 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.utils import configclass + +from isaaclab_rl.rsl_rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoAlgorithmCfg, +) + + +@configclass +class AnymalCFlatPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 500 + save_interval = 50 + experiment_name = "anymal_c_flat_direct" + empirical_normalization = False + policy = RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_hidden_dims=[128, 128, 128], + critic_hidden_dims=[128, 128, 128], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.005, + 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 AnymalCRoughPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 1500 + save_interval = 50 + experiment_name = "anymal_c_rough_direct" + 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.005, + 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, + ) diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_flat_ppo_cfg.yaml b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_flat_ppo_cfg.yaml new file mode 100644 index 00000000..aa5828e7 --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_flat_ppo_cfg.yaml @@ -0,0 +1,80 @@ +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: [128, 128, 128] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [128, 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 + rollouts: 24 + learning_epochs: 5 + mini_batches: 4 + 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: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.005 + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 0.6 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "anymal_c_flat_direct" + 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/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_rough_ppo_cfg.yaml b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_rough_ppo_cfg.yaml new file mode 100644 index 00000000..1c72b8fb --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/agents/skrl_rough_ppo_cfg.yaml @@ -0,0 +1,80 @@ +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: [512, 256, 128] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [512, 256, 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 + rollouts: 24 + learning_epochs: 5 + mini_batches: 4 + 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: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.005 + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 0.6 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "anymal_c_rough_direct" + 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/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env.py b/source/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env.py new file mode 100644 index 00000000..fd2ee24a --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env.py @@ -0,0 +1,195 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +import gymnasium as gym +import torch + +import isaaclab.sim as sim_utils +from isaaclab.assets import Articulation +from isaaclab.envs import DirectRLEnv +from isaaclab.sensors import ContactSensor, RayCaster + +from .anymal_c_env_cfg import AnymalCFlatEnvCfg, AnymalCRoughEnvCfg + + +class AnymalCEnv(DirectRLEnv): + cfg: AnymalCFlatEnvCfg | AnymalCRoughEnvCfg + + def __init__(self, cfg: AnymalCFlatEnvCfg | AnymalCRoughEnvCfg, render_mode: str | None = None, **kwargs): + super().__init__(cfg, render_mode, **kwargs) + + # Joint position command (deviation from default joint positions) + self._actions = torch.zeros(self.num_envs, gym.spaces.flatdim(self.single_action_space), device=self.device) + self._previous_actions = torch.zeros( + self.num_envs, gym.spaces.flatdim(self.single_action_space), device=self.device + ) + + # X/Y linear velocity and yaw angular velocity commands + self._commands = torch.zeros(self.num_envs, 3, device=self.device) + + # Logging + self._episode_sums = { + key: torch.zeros(self.num_envs, dtype=torch.float, device=self.device) + for key in [ + "track_lin_vel_xy_exp", + "track_ang_vel_z_exp", + "lin_vel_z_l2", + "ang_vel_xy_l2", + "dof_torques_l2", + "dof_acc_l2", + "action_rate_l2", + "feet_air_time", + "undesired_contacts", + "flat_orientation_l2", + ] + } + # Get specific body indices + self._base_id, _ = self._contact_sensor.find_bodies("base") + self._feet_ids, _ = self._contact_sensor.find_bodies(".*FOOT") + self._undesired_contact_body_ids, _ = self._contact_sensor.find_bodies(".*THIGH") + + def _setup_scene(self): + self._robot = Articulation(self.cfg.robot) + self.scene.articulations["robot"] = self._robot + self._contact_sensor = ContactSensor(self.cfg.contact_sensor) + self.scene.sensors["contact_sensor"] = self._contact_sensor + if isinstance(self.cfg, AnymalCRoughEnvCfg): + # we add a height scanner for perceptive locomotion + self._height_scanner = RayCaster(self.cfg.height_scanner) + self.scene.sensors["height_scanner"] = self._height_scanner + self.cfg.terrain.num_envs = self.scene.cfg.num_envs + self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing + self._terrain = self.cfg.terrain.class_type(self.cfg.terrain) + # clone, filter, and replicate + self.scene.clone_environments(copy_from_source=False) + self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) + # add lights + light_cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75)) + light_cfg.func("/World/Light", light_cfg) + + def _pre_physics_step(self, actions: torch.Tensor): + self._actions = actions.clone() + self._processed_actions = self.cfg.action_scale * self._actions + self._robot.data.default_joint_pos + + def _apply_action(self): + self._robot.set_joint_position_target(self._processed_actions) + + def _get_observations(self) -> dict: + self._previous_actions = self._actions.clone() + height_data = None + if isinstance(self.cfg, AnymalCRoughEnvCfg): + height_data = ( + self._height_scanner.data.pos_w[:, 2].unsqueeze(1) - self._height_scanner.data.ray_hits_w[..., 2] - 0.5 + ).clip(-1.0, 1.0) + obs = torch.cat( + [ + tensor + for tensor in ( + self._robot.data.root_lin_vel_b, + self._robot.data.root_ang_vel_b, + self._robot.data.projected_gravity_b, + self._commands, + self._robot.data.joint_pos - self._robot.data.default_joint_pos, + self._robot.data.joint_vel, + height_data, + self._actions, + ) + if tensor is not None + ], + dim=-1, + ) + observations = {"policy": obs} + return observations + + def _get_rewards(self) -> torch.Tensor: + # linear velocity tracking + lin_vel_error = torch.sum(torch.square(self._commands[:, :2] - self._robot.data.root_lin_vel_b[:, :2]), dim=1) + lin_vel_error_mapped = torch.exp(-lin_vel_error / 0.25) + # yaw rate tracking + yaw_rate_error = torch.square(self._commands[:, 2] - self._robot.data.root_ang_vel_b[:, 2]) + yaw_rate_error_mapped = torch.exp(-yaw_rate_error / 0.25) + # z velocity tracking + z_vel_error = torch.square(self._robot.data.root_lin_vel_b[:, 2]) + # angular velocity x/y + ang_vel_error = torch.sum(torch.square(self._robot.data.root_ang_vel_b[:, :2]), dim=1) + # joint torques + joint_torques = torch.sum(torch.square(self._robot.data.applied_torque), dim=1) + # joint acceleration + joint_accel = torch.sum(torch.square(self._robot.data.joint_acc), dim=1) + # action rate + action_rate = torch.sum(torch.square(self._actions - self._previous_actions), dim=1) + # feet air time + first_contact = self._contact_sensor.compute_first_contact(self.step_dt)[:, self._feet_ids] + last_air_time = self._contact_sensor.data.last_air_time[:, self._feet_ids] + air_time = torch.sum((last_air_time - 0.5) * first_contact, dim=1) * ( + torch.norm(self._commands[:, :2], dim=1) > 0.1 + ) + # undesired contacts + net_contact_forces = self._contact_sensor.data.net_forces_w_history + is_contact = ( + torch.max(torch.norm(net_contact_forces[:, :, self._undesired_contact_body_ids], dim=-1), dim=1)[0] > 1.0 + ) + contacts = torch.sum(is_contact, dim=1) + # flat orientation + flat_orientation = torch.sum(torch.square(self._robot.data.projected_gravity_b[:, :2]), dim=1) + + rewards = { + "track_lin_vel_xy_exp": lin_vel_error_mapped * self.cfg.lin_vel_reward_scale * self.step_dt, + "track_ang_vel_z_exp": yaw_rate_error_mapped * self.cfg.yaw_rate_reward_scale * self.step_dt, + "lin_vel_z_l2": z_vel_error * self.cfg.z_vel_reward_scale * self.step_dt, + "ang_vel_xy_l2": ang_vel_error * self.cfg.ang_vel_reward_scale * self.step_dt, + "dof_torques_l2": joint_torques * self.cfg.joint_torque_reward_scale * self.step_dt, + "dof_acc_l2": joint_accel * self.cfg.joint_accel_reward_scale * self.step_dt, + "action_rate_l2": action_rate * self.cfg.action_rate_reward_scale * self.step_dt, + "feet_air_time": air_time * self.cfg.feet_air_time_reward_scale * self.step_dt, + "undesired_contacts": contacts * self.cfg.undesired_contact_reward_scale * self.step_dt, + "flat_orientation_l2": flat_orientation * self.cfg.flat_orientation_reward_scale * self.step_dt, + } + reward = torch.sum(torch.stack(list(rewards.values())), dim=0) + # Logging + for key, value in rewards.items(): + self._episode_sums[key] += value + return reward + + def _get_dones(self) -> tuple[torch.Tensor, torch.Tensor]: + time_out = self.episode_length_buf >= self.max_episode_length - 1 + net_contact_forces = self._contact_sensor.data.net_forces_w_history + died = torch.any(torch.max(torch.norm(net_contact_forces[:, :, self._base_id], dim=-1), dim=1)[0] > 1.0, dim=1) + return died, time_out + + def _reset_idx(self, env_ids: torch.Tensor | None): + if env_ids is None or len(env_ids) == self.num_envs: + env_ids = self._robot._ALL_INDICES + self._robot.reset(env_ids) + super()._reset_idx(env_ids) + if len(env_ids) == self.num_envs: + # Spread out the resets to avoid spikes in training when many environments reset at a similar time + self.episode_length_buf[:] = torch.randint_like(self.episode_length_buf, high=int(self.max_episode_length)) + self._actions[env_ids] = 0.0 + self._previous_actions[env_ids] = 0.0 + # Sample new commands + self._commands[env_ids] = torch.zeros_like(self._commands[env_ids]).uniform_(-1.0, 1.0) + # Reset robot state + joint_pos = self._robot.data.default_joint_pos[env_ids] + joint_vel = self._robot.data.default_joint_vel[env_ids] + default_root_state = self._robot.data.default_root_state[env_ids] + default_root_state[:, :3] += self._terrain.env_origins[env_ids] + self._robot.write_root_pose_to_sim(default_root_state[:, :7], env_ids) + self._robot.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids) + self._robot.write_joint_state_to_sim(joint_pos, joint_vel, None, env_ids) + # Logging + extras = dict() + for key in self._episode_sums.keys(): + episodic_sum_avg = torch.mean(self._episode_sums[key][env_ids]) + extras["Episode_Reward/" + key] = episodic_sum_avg / self.max_episode_length_s + self._episode_sums[key][env_ids] = 0.0 + self.extras["log"] = dict() + self.extras["log"].update(extras) + extras = dict() + extras["Episode_Termination/base_contact"] = torch.count_nonzero(self.reset_terminated[env_ids]).item() + extras["Episode_Termination/time_out"] = torch.count_nonzero(self.reset_time_outs[env_ids]).item() + self.extras["log"].update(extras) diff --git a/source/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env_cfg.py new file mode 100644 index 00000000..71b75594 --- /dev/null +++ b/source/ext_template/ext_template/tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -0,0 +1,150 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import isaaclab.envs.mdp as mdp +import isaaclab.sim as sim_utils +from isaaclab.assets import ArticulationCfg +from isaaclab.envs import DirectRLEnvCfg +from isaaclab.managers import EventTermCfg as EventTerm +from isaaclab.managers import SceneEntityCfg +from isaaclab.scene import InteractiveSceneCfg +from isaaclab.sensors import ContactSensorCfg, RayCasterCfg, patterns +from isaaclab.sim import SimulationCfg +from isaaclab.terrains import TerrainImporterCfg +from isaaclab.utils import configclass + +## +# Pre-defined configs +## +# from isaaclab_assets.anymal import ANYMAL_C_CFG # isort: skip +from ext_template.assets import ANYMAL_C_CFG +from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: skip + + +@configclass +class EventCfg: + """Configuration for randomization.""" + + physics_material = EventTerm( + func=mdp.randomize_rigid_body_material, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=".*"), + "static_friction_range": (0.8, 0.8), + "dynamic_friction_range": (0.6, 0.6), + "restitution_range": (0.0, 0.0), + "num_buckets": 64, + }, + ) + + add_base_mass = EventTerm( + func=mdp.randomize_rigid_body_mass, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names="base"), + "mass_distribution_params": (-5.0, 5.0), + "operation": "add", + }, + ) + + +@configclass +class AnymalCFlatEnvCfg(DirectRLEnvCfg): + # env + episode_length_s = 20.0 + decimation = 4 + action_scale = 0.5 + action_space = 12 + observation_space = 48 + state_space = 0 + + # simulation + sim: SimulationCfg = SimulationCfg( + dt=1 / 200, + render_interval=decimation, + disable_contact_processing=True, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + restitution=0.0, + ), + ) + terrain = TerrainImporterCfg( + prim_path="/World/ground", + terrain_type="plane", + collision_group=-1, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + restitution=0.0, + ), + debug_vis=False, + ) + + # scene + scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=4096, env_spacing=4.0, replicate_physics=True) + + # events + events: EventCfg = EventCfg() + + # robot + robot: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="/World/envs/env_.*/Robot") + contact_sensor: ContactSensorCfg = ContactSensorCfg( + prim_path="/World/envs/env_.*/Robot/.*", history_length=3, update_period=0.005, track_air_time=True + ) + + # reward scales + lin_vel_reward_scale = 1.0 + yaw_rate_reward_scale = 0.5 + z_vel_reward_scale = -2.0 + ang_vel_reward_scale = -0.05 + joint_torque_reward_scale = -2.5e-5 + joint_accel_reward_scale = -2.5e-7 + action_rate_reward_scale = -0.01 + feet_air_time_reward_scale = 0.5 + undesired_contact_reward_scale = -1.0 + flat_orientation_reward_scale = -5.0 + + +@configclass +class AnymalCRoughEnvCfg(AnymalCFlatEnvCfg): + # env + observation_space = 235 + + terrain = TerrainImporterCfg( + prim_path="/World/ground", + terrain_type="generator", + terrain_generator=ROUGH_TERRAINS_CFG, + max_init_terrain_level=9, + collision_group=-1, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + ), + visual_material=sim_utils.MdlFileCfg( + mdl_path="{NVIDIA_NUCLEUS_DIR}/Materials/Base/Architecture/Shingles_01.mdl", + project_uvw=True, + ), + debug_vis=False, + ) + + # we add a height scanner for perceptive locomotion + height_scanner = RayCasterCfg( + prim_path="/World/envs/env_.*/Robot/base", + offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)), + attach_yaw_only=True, + pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]), + debug_vis=False, + mesh_prim_paths=["/World/ground"], + ) + + # reward scales (override from flat config) + flat_orientation_reward_scale = 0.0 diff --git a/source/ext_template/ext_template/tasks/manager_based/__init__.py b/source/ext_template/ext_template/tasks/manager_based/__init__.py new file mode 100644 index 00000000..75d74f77 --- /dev/null +++ b/source/ext_template/ext_template/tasks/manager_based/__init__.py @@ -0,0 +1,10 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +""" +Config-based workflow environments. +""" + +import gymnasium as gym \ No newline at end of file diff --git a/source/ext_template/ext_template/tasks/locomotion/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/agents/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/agents/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/agents/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/agents/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/agents/rsl_rl_ppo_cfg.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/agents/rsl_rl_ppo_cfg.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/agents/rsl_rl_ppo_cfg.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/agents/rsl_rl_ppo_cfg.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/flat_env_cfg.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/flat_env_cfg.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py similarity index 92% rename from source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py index 289b07fd..6c6fc1a1 100644 --- a/source/ext_template/ext_template/tasks/locomotion/velocity/config/anymal_d/rough_env_cfg.py +++ b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py @@ -1,6 +1,6 @@ from isaaclab.utils import configclass -from ext_template.tasks.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg +from ext_template.tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg ## # Pre-defined configs diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/mdp/__init__.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/__init__.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/mdp/__init__.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/__init__.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/mdp/curriculums.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/curriculums.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/mdp/curriculums.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/curriculums.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/mdp/rewards.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/rewards.py similarity index 100% rename from source/ext_template/ext_template/tasks/locomotion/velocity/mdp/rewards.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/mdp/rewards.py diff --git a/source/ext_template/ext_template/tasks/locomotion/velocity/velocity_env_cfg.py b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/velocity_env_cfg.py similarity index 99% rename from source/ext_template/ext_template/tasks/locomotion/velocity/velocity_env_cfg.py rename to source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index 27a3ea74..184b8c74 100644 --- a/source/ext_template/ext_template/tasks/locomotion/velocity/velocity_env_cfg.py +++ b/source/ext_template/ext_template/tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -19,7 +19,7 @@ from isaaclab.utils import configclass from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise -import ext_template.tasks.locomotion.velocity.mdp as mdp +import ext_template.tasks.manager_based.locomotion.velocity.mdp as mdp ## # Pre-defined configs