|
| 1 | +# Copyright (c) 2022-2024, The Isaac Lab Project Developers. |
| 2 | +# All rights reserved. |
| 3 | +# |
| 4 | +# SPDX-License-Identifier: BSD-3-Clause |
| 5 | + |
| 6 | +""" |
| 7 | +This script creates a simple environment with a floating cube. The cube is controlled by a PD |
| 8 | +controller to track an arbitrary target position. |
| 9 | +
|
| 10 | +While going through this tutorial, we recommend you to pay attention to how a custom action term |
| 11 | +is defined. The action term is responsible for processing the raw actions and applying them to the |
| 12 | +scene entities. The rest of the environment is similar to the previous tutorials. |
| 13 | +
|
| 14 | +.. code-block:: bash |
| 15 | +
|
| 16 | + # Run the script |
| 17 | + ./isaaclab.sh -p source/standalone/tutorials/03_envs/create_cube_base_env.py --num_envs 32 |
| 18 | +""" |
| 19 | + |
| 20 | +from __future__ import annotations |
| 21 | + |
| 22 | +"""Launch Isaac Sim Simulator first.""" |
| 23 | + |
| 24 | +from omni.isaac.lab.app import AppLauncher, run_tests |
| 25 | + |
| 26 | +# Can set this to False to see the GUI for debugging |
| 27 | +HEADLESS = False |
| 28 | + |
| 29 | +# launch omniverse app |
| 30 | +app_launcher = AppLauncher(headless=HEADLESS, enable_cameras=True) |
| 31 | +simulation_app = app_launcher.app |
| 32 | + |
| 33 | +"""Rest everything follows.""" |
| 34 | + |
| 35 | +import torch |
| 36 | +import unittest |
| 37 | + |
| 38 | +import omni.isaac.lab.envs.mdp as mdp |
| 39 | +import omni.isaac.lab.sim as sim_utils |
| 40 | +from omni.isaac.lab.assets import AssetBaseCfg, RigidObject, RigidObjectCfg |
| 41 | +from omni.isaac.lab.envs import ManagerBasedEnv, ManagerBasedEnvCfg |
| 42 | +from omni.isaac.lab.managers import ActionTerm, ActionTermCfg |
| 43 | +from omni.isaac.lab.managers import EventTermCfg as EventTerm |
| 44 | +from omni.isaac.lab.managers import ObservationGroupCfg as ObsGroup |
| 45 | +from omni.isaac.lab.managers import ObservationTermCfg as ObsTerm |
| 46 | +from omni.isaac.lab.managers import SceneEntityCfg |
| 47 | +from omni.isaac.lab.scene import InteractiveSceneCfg |
| 48 | +from omni.isaac.lab.terrains import TerrainImporterCfg |
| 49 | +from omni.isaac.lab.utils import configclass |
| 50 | + |
| 51 | +## |
| 52 | +# Custom action term |
| 53 | +## |
| 54 | + |
| 55 | + |
| 56 | +class CubeActionTerm(ActionTerm): |
| 57 | + """Simple action term that implements a PD controller to track a target position. |
| 58 | +
|
| 59 | + The action term is applied to the cube asset. It involves two steps: |
| 60 | +
|
| 61 | + 1. **Process the raw actions**: Typically, this includes any transformations of the raw actions |
| 62 | + that are required to map them to the desired space. This is called once per environment step. |
| 63 | + 2. **Apply the processed actions**: This step applies the processed actions to the asset. |
| 64 | + It is called once per simulation step. |
| 65 | +
|
| 66 | + In this case, the action term simply applies the raw actions to the cube asset. The raw actions |
| 67 | + are the desired target positions of the cube in the environment frame. The pre-processing step |
| 68 | + simply copies the raw actions to the processed actions as no additional processing is required. |
| 69 | + The processed actions are then applied to the cube asset by implementing a PD controller to |
| 70 | + track the target position. |
| 71 | + """ |
| 72 | + |
| 73 | + _asset: RigidObject |
| 74 | + """The articulation asset on which the action term is applied.""" |
| 75 | + |
| 76 | + def __init__(self, cfg: CubeActionTermCfg, env: ManagerBasedEnv): |
| 77 | + # call super constructor |
| 78 | + super().__init__(cfg, env) |
| 79 | + # create buffers |
| 80 | + self._raw_actions = torch.zeros(env.num_envs, 3, device=self.device) |
| 81 | + self._processed_actions = torch.zeros(env.num_envs, 3, device=self.device) |
| 82 | + self._vel_command = torch.zeros(self.num_envs, 6, device=self.device) |
| 83 | + # gains of controller |
| 84 | + self.p_gain = cfg.p_gain |
| 85 | + self.d_gain = cfg.d_gain |
| 86 | + |
| 87 | + """ |
| 88 | + Properties. |
| 89 | + """ |
| 90 | + |
| 91 | + @property |
| 92 | + def action_dim(self) -> int: |
| 93 | + return self._raw_actions.shape[1] |
| 94 | + |
| 95 | + @property |
| 96 | + def raw_actions(self) -> torch.Tensor: |
| 97 | + return self._raw_actions |
| 98 | + |
| 99 | + @property |
| 100 | + def processed_actions(self) -> torch.Tensor: |
| 101 | + return self._processed_actions |
| 102 | + |
| 103 | + """ |
| 104 | + Operations |
| 105 | + """ |
| 106 | + |
| 107 | + def process_actions(self, actions: torch.Tensor): |
| 108 | + # store the raw actions |
| 109 | + self._raw_actions[:] = actions |
| 110 | + # no-processing of actions |
| 111 | + self._processed_actions[:] = self._raw_actions[:] |
| 112 | + |
| 113 | + def apply_actions(self): |
| 114 | + # implement a PD controller to track the target position |
| 115 | + pos_error = self._processed_actions - (self._asset.data.root_pos_w - self._env.scene.env_origins) |
| 116 | + vel_error = -self._asset.data.root_lin_vel_w |
| 117 | + # set velocity targets |
| 118 | + self._vel_command[:, :3] = self.p_gain * pos_error + self.d_gain * vel_error |
| 119 | + self._asset.write_root_velocity_to_sim(self._vel_command) |
| 120 | + |
| 121 | + |
| 122 | +@configclass |
| 123 | +class CubeActionTermCfg(ActionTermCfg): |
| 124 | + """Configuration for the cube action term.""" |
| 125 | + |
| 126 | + class_type: type = CubeActionTerm |
| 127 | + """The class corresponding to the action term.""" |
| 128 | + |
| 129 | + p_gain: float = 5.0 |
| 130 | + """Proportional gain of the PD controller.""" |
| 131 | + d_gain: float = 0.5 |
| 132 | + """Derivative gain of the PD controller.""" |
| 133 | + |
| 134 | + |
| 135 | +## |
| 136 | +# Custom observation term |
| 137 | +## |
| 138 | + |
| 139 | + |
| 140 | +def base_position(env: ManagerBasedEnv, asset_cfg: SceneEntityCfg) -> torch.Tensor: |
| 141 | + """Root linear velocity in the asset's root frame.""" |
| 142 | + # extract the used quantities (to enable type-hinting) |
| 143 | + asset: RigidObject = env.scene[asset_cfg.name] |
| 144 | + return asset.data.root_pos_w - env.scene.env_origins |
| 145 | + |
| 146 | + |
| 147 | +## |
| 148 | +# Scene definition |
| 149 | +## |
| 150 | + |
| 151 | + |
| 152 | +@configclass |
| 153 | +class MySceneCfg(InteractiveSceneCfg): |
| 154 | + """Example scene configuration. |
| 155 | +
|
| 156 | + The scene comprises of a ground plane, light source and floating cubes (gravity disabled). |
| 157 | + """ |
| 158 | + |
| 159 | + # add terrain |
| 160 | + terrain = TerrainImporterCfg(prim_path="/World/ground", terrain_type="plane", debug_vis=False) |
| 161 | + |
| 162 | + # add cube |
| 163 | + cube: RigidObjectCfg = RigidObjectCfg( |
| 164 | + prim_path="{ENV_REGEX_NS}/cube", |
| 165 | + spawn=sim_utils.CuboidCfg( |
| 166 | + size=(0.2, 0.2, 0.2), |
| 167 | + rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0, disable_gravity=True), |
| 168 | + mass_props=sim_utils.MassPropertiesCfg(mass=1.0), |
| 169 | + physics_material=sim_utils.RigidBodyMaterialCfg(), |
| 170 | + visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 0.0)), |
| 171 | + ), |
| 172 | + init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 5)), |
| 173 | + ) |
| 174 | + |
| 175 | + # lights |
| 176 | + light = AssetBaseCfg( |
| 177 | + prim_path="/World/light", |
| 178 | + spawn=sim_utils.DistantLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0), |
| 179 | + ) |
| 180 | + |
| 181 | + |
| 182 | +## |
| 183 | +# Environment settings |
| 184 | +## |
| 185 | + |
| 186 | + |
| 187 | +@configclass |
| 188 | +class ActionsCfg: |
| 189 | + """Action specifications for the MDP.""" |
| 190 | + |
| 191 | + joint_pos = CubeActionTermCfg(asset_name="cube") |
| 192 | + |
| 193 | + |
| 194 | +@configclass |
| 195 | +class ObservationsCfg: |
| 196 | + """Observation specifications for the MDP.""" |
| 197 | + |
| 198 | + @configclass |
| 199 | + class PolicyCfg(ObsGroup): |
| 200 | + """Observations for policy group.""" |
| 201 | + |
| 202 | + # cube velocity |
| 203 | + position = ObsTerm(func=base_position, params={"asset_cfg": SceneEntityCfg("cube")}) |
| 204 | + |
| 205 | + def __post_init__(self): |
| 206 | + self.enable_corruption = True |
| 207 | + self.concatenate_terms = True |
| 208 | + |
| 209 | + # observation groups |
| 210 | + policy: PolicyCfg = PolicyCfg() |
| 211 | + |
| 212 | + |
| 213 | +@configclass |
| 214 | +class EventCfg: |
| 215 | + """Configuration for events.""" |
| 216 | + |
| 217 | + reset_base = EventTerm( |
| 218 | + func=mdp.reset_root_state_uniform, |
| 219 | + mode="reset", |
| 220 | + params={ |
| 221 | + "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, |
| 222 | + "velocity_range": { |
| 223 | + "x": (-0.5, 0.5), |
| 224 | + "y": (-0.5, 0.5), |
| 225 | + "z": (-0.5, 0.5), |
| 226 | + }, |
| 227 | + "asset_cfg": SceneEntityCfg("cube"), |
| 228 | + }, |
| 229 | + ) |
| 230 | + |
| 231 | + randomize_scale = EventTerm( |
| 232 | + func=mdp.randomize_scale, |
| 233 | + mode="scene", |
| 234 | + params={ |
| 235 | + "scale_range": {"x": (0.5, 1.5), "y": (0.5, 1.5), "z": (0.5, 1.5)}, |
| 236 | + "asset_cfg": SceneEntityCfg("cube"), |
| 237 | + }, |
| 238 | + ) |
| 239 | + |
| 240 | + |
| 241 | +## |
| 242 | +# Environment configuration |
| 243 | +## |
| 244 | + |
| 245 | + |
| 246 | +@configclass |
| 247 | +class CubeEnvCfg(ManagerBasedEnvCfg): |
| 248 | + """Configuration for the locomotion velocity-tracking environment.""" |
| 249 | + |
| 250 | + # Scene settings |
| 251 | + scene: MySceneCfg = MySceneCfg(num_envs=64, env_spacing=2.5, replicate_physics=False) |
| 252 | + # Basic settings |
| 253 | + observations: ObservationsCfg = ObservationsCfg() |
| 254 | + actions: ActionsCfg = ActionsCfg() |
| 255 | + events: EventCfg = EventCfg() |
| 256 | + |
| 257 | + def __post_init__(self): |
| 258 | + """Post initialization.""" |
| 259 | + # general settings |
| 260 | + self.decimation = 2 |
| 261 | + # simulation settings |
| 262 | + self.sim.dt = 0.01 |
| 263 | + self.sim.physics_material = self.scene.terrain.physics_material |
| 264 | + |
| 265 | + |
| 266 | +class TestScaleRandomization(unittest.TestCase): |
| 267 | + """Test for texture randomization""" |
| 268 | + |
| 269 | + """ |
| 270 | + Tests |
| 271 | + """ |
| 272 | + |
| 273 | + def test_scale_randomization(self): |
| 274 | + """Main function.""" |
| 275 | + |
| 276 | + # setup base environment |
| 277 | + env = ManagerBasedEnv(cfg=CubeEnvCfg()) |
| 278 | + # setup target position commands |
| 279 | + target_position = torch.rand(env.num_envs, 3, device=env.device) * 2 |
| 280 | + target_position[:, 2] += 2.0 |
| 281 | + # offset all targets so that they move to the world origin |
| 282 | + target_position -= env.scene.env_origins |
| 283 | + |
| 284 | + # simulate physics |
| 285 | + count = 0 |
| 286 | + obs, _ = env.reset() |
| 287 | + while simulation_app.is_running(): |
| 288 | + with torch.inference_mode(): |
| 289 | + # reset |
| 290 | + if count % 300 == 0: |
| 291 | + count = 0 |
| 292 | + obs, _ = env.reset() |
| 293 | + print("-" * 80) |
| 294 | + print("[INFO]: Resetting environment...") |
| 295 | + # step env |
| 296 | + obs, _ = env.step(target_position) |
| 297 | + # print mean squared position error between target and current position |
| 298 | + error = torch.norm(obs["policy"] - target_position).mean().item() |
| 299 | + print(f"[Step: {count:04d}]: Mean position error: {error:.4f}") |
| 300 | + # update counter |
| 301 | + count += 1 |
| 302 | + |
| 303 | + |
| 304 | +if __name__ == "__main__": |
| 305 | + run_tests() |
| 306 | + # # run the main function |
| 307 | + # main() |
| 308 | + # # close sim app |
| 309 | + # simulation_app.close() |
0 commit comments