Skip to content

Commit

Permalink
Updated code
Browse files Browse the repository at this point in the history
  • Loading branch information
Dhoeller19 committed Jul 17, 2024
1 parent 4ee25f0 commit 85a6fb6
Show file tree
Hide file tree
Showing 15 changed files with 18 additions and 30 deletions.
2 changes: 1 addition & 1 deletion docs/source/how-to/record_animation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ Here we run the state-machine example and record the animation of the simulation

.. code-block:: bash
./isaaclab.sh -p source/standalone/environments/state_machine/lift_cube_sm.py --num_envs 8 --cpu --disable_fabric
./isaaclab.sh -p source/standalone/environments/state_machine/lift_cube_sm.py --num_envs 8 --device cpu --disable_fabric
On running the script, the Isaac Lab UI window opens with the button "Record Animation" in the toolbar.
Expand Down
4 changes: 2 additions & 2 deletions docs/source/setup/sample.rst
Original file line number Diff line number Diff line change
Expand Up @@ -182,8 +182,8 @@ from the environments into the respective libraries function argument and return
# install python module (for stable-baselines3)
./isaaclab.sh -i sb3
# run script for training
# note: we enable cpu flag since SB3 doesn't optimize for GPU anyway
./isaaclab.sh -p source/standalone/workflows/sb3/train.py --task Isaac-Cartpole-v0 --headless --cpu
# note: we set the device to cpu since SB3 doesn't optimize for GPU anyway
./isaaclab.sh -p source/standalone/workflows/sb3/train.py --task Isaac-Cartpole-v0 --headless --device cpu
# run script for playing with 32 environments
./isaaclab.sh -p source/standalone/workflows/sb3/play.py --task Isaac-Cartpole-v0 --num_envs 32 --checkpoint /PATH/TO/model.zip
Expand Down
6 changes: 3 additions & 3 deletions docs/source/tutorials/03_envs/register_rl_env_gym.rst
Original file line number Diff line number Diff line change
Expand Up @@ -152,11 +152,11 @@ Now that we have gone through the code, let's run the script and see the result:
This should open a stage with everything similar to the :ref:`tutorial-create-manager-rl-env` tutorial.
To stop the simulation, you can either close the window, or press ``Ctrl+C`` in the terminal.

In addition, you can also change the simulation device from GPU to CPU by adding the ``--cpu`` flag:
In addition, you can also change the simulation device from GPU to CPU by setting the value of the ``--device`` flag explicitly:

.. code-block:: bash
./isaaclab.sh -p source/standalone/environments/random_agent.py --task Isaac-Cartpole-v0 --num_envs 32 --cpu
./isaaclab.sh -p source/standalone/environments/random_agent.py --task Isaac-Cartpole-v0 --num_envs 32 --device cpu
With the ``--cpu`` flag, the simulation will run on the CPU. This is useful for debugging the simulation.
With the ``--device cpu`` flag, the simulation will run on the CPU. This is useful for debugging the simulation.
However, the simulation will run much slower than on the GPU.
4 changes: 1 addition & 3 deletions source/standalone/demos/bipeds.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,7 @@ def main():
"""Main function."""

# Load kit helper
sim = SimulationContext(
sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False, dt=0.01, physx=sim_utils.PhysxCfg(use_gpu=False))
)
sim = SimulationContext(sim_utils.SimulationCfg(device="cpu", dt=0.01))
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])

Expand Down
4 changes: 1 addition & 3 deletions source/standalone/demos/quadcopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,7 @@ def main():
"""Main function."""

# Load kit helper
sim = SimulationContext(
sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False, dt=0.005, physx=sim_utils.PhysxCfg(use_gpu=False))
)
sim = SimulationContext(sim_utils.SimulationCfg(device="cpu", dt=0.005))
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])

Expand Down
3 changes: 1 addition & 2 deletions source/standalone/environments/random_agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Random agent for Isaac Lab environments.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -41,7 +40,7 @@ def main():
"""Random actions agent with Isaac Lab environment."""
# create environment configuration
env_cfg = parse_env_cfg(
args_cli.task, use_gpu=not args_cli.cpu, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
)
# create environment
env = gym.make(args_cli.task, cfg=env_cfg)
Expand Down
3 changes: 1 addition & 2 deletions source/standalone/environments/state_machine/lift_cube_sm.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Pick and lift state machine for lift environments.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -242,7 +241,7 @@ def main():
# parse configuration
env_cfg: LiftEnvCfg = parse_env_cfg(
"Isaac-Lift-Cube-Franka-IK-Abs-v0",
use_gpu=not args_cli.cpu,
device=args_cli.device,
num_envs=args_cli.num_envs,
use_fabric=not args_cli.disable_fabric,
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Pick and lift state machine for cabinet environments.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -265,7 +264,7 @@ def main():
# parse configuration
env_cfg: CabinetEnvCfg = parse_env_cfg(
"Isaac-Open-Drawer-Franka-IK-Abs-v0",
use_gpu=not args_cli.cpu,
device=args_cli.device,
num_envs=args_cli.num_envs,
use_fabric=not args_cli.disable_fabric,
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Keyboard teleoperation for Isaac Lab environments.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -63,7 +62,7 @@ def main():
"""Running keyboard teleoperation with Isaac Lab manipulation environment."""
# parse configuration
env_cfg = parse_env_cfg(
args_cli.task, use_gpu=not args_cli.cpu, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
)
# modify configuration
env_cfg.terminations.time_out = None
Expand Down
3 changes: 1 addition & 2 deletions source/standalone/environments/zero_agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Zero agent for Isaac Lab environments.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -41,7 +40,7 @@ def main():
"""Zero actions agent with Isaac Lab environment."""
# parse configuration
env_cfg = parse_env_cfg(
args_cli.task, use_gpu=not args_cli.cpu, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
)
# create environment
env = gym.make(args_cli.task, cfg=env_cfg)
Expand Down
2 changes: 1 addition & 1 deletion source/standalone/tutorials/01_assets/run_articulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula
def main():
"""Main function."""
# Load kit helper
sim_cfg = sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False)
sim_cfg = sim_utils.SimulationCfg(device="cpu")
sim = SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
Expand Down
2 changes: 1 addition & 1 deletion source/standalone/tutorials/02_scene/create_scene.py
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
def main():
"""Main function."""
# Load kit helper
sim_cfg = sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False)
sim_cfg = sim_utils.SimulationCfg(device="cpu")
sim = SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
Expand Down
3 changes: 1 addition & 2 deletions source/standalone/tutorials/04_sensors/run_usd_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="This script demonstrates how to use the camera sensor.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU device for camera output.")
parser.add_argument(
"--draw",
action="store_true",
Expand Down Expand Up @@ -276,7 +275,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
def main():
"""Main function."""
# Load simulation context
sim_cfg = sim_utils.SimulationCfg(device="cpu" if args_cli.cpu else "cuda")
sim_cfg = sim_utils.SimulationCfg(device=args_cli.device)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
Expand Down
3 changes: 1 addition & 2 deletions source/standalone/workflows/skrl/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

# add argparse arguments
parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from skrl.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -70,7 +69,7 @@ def main():
skrl.config.jax.backend = "jax" if args_cli.ml_framework == "jax" else "numpy"
# parse configuration
env_cfg = parse_env_cfg(
args_cli.task, use_gpu=not args_cli.cpu, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
)
experiment_cfg = load_cfg_from_registry(args_cli.task, "skrl_cfg_entry_point")

Expand Down
3 changes: 1 addition & 2 deletions source/standalone/workflows/skrl/train.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
parser.add_argument("--video_interval", type=int, default=2000, help="Interval between video recordings (in steps).")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument(
"--disable_fabric", action="store_true", default=False, help="Disable fabric and use USD I/O operations."
)
Expand Down Expand Up @@ -92,7 +91,7 @@ def main():

# parse configuration
env_cfg = parse_env_cfg(
args_cli.task, use_gpu=not args_cli.cpu, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric
)
experiment_cfg = load_cfg_from_registry(args_cli.task, "skrl_cfg_entry_point")

Expand Down

0 comments on commit 85a6fb6

Please sign in to comment.