Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
48 commits
Select commit Hold shift + click to select a range
d4dc70e
init
matthewtrepte Nov 8, 2025
d70b0d8
initial impl
matthewtrepte Nov 11, 2025
d5fcc05
add scene data provider abstraction layer
matthewtrepte Nov 12, 2025
a1e8ec2
bug fix
matthewtrepte Nov 12, 2025
c927485
clean
matthewtrepte Nov 12, 2025
1b24ba5
wip
matthewtrepte Nov 13, 2025
b67e00e
add rerun viz
matthewtrepte Nov 15, 2025
30116c0
clean
matthewtrepte Nov 15, 2025
95d9429
clean
matthewtrepte Nov 15, 2025
f1ca9db
try new newton
matthewtrepte Nov 19, 2025
a8c9d07
wip
matthewtrepte Nov 19, 2025
7ee435f
adding feats
matthewtrepte Nov 19, 2025
011c373
wip
matthewtrepte Nov 19, 2025
c0a3b1e
cleaning up
matthewtrepte Nov 19, 2025
6f4ff19
clean
matthewtrepte Nov 19, 2025
3d154aa
add OV ui auto enabling to live plots
matthewtrepte Nov 19, 2025
0f8dda3
fb draft
matthewtrepte Nov 21, 2025
e4aceab
wip
matthewtrepte Nov 21, 2025
0f99eaa
clean
matthewtrepte Nov 21, 2025
a5f8256
prepare for merge;
matthewtrepte Nov 21, 2025
ecb66af
clean before review
matthewtrepte Nov 21, 2025
7562067
default to no viz
matthewtrepte Nov 21, 2025
52ae2f3
Update simulation_cfg.py
matthewtrepte Nov 21, 2025
17aa1e5
Update simulation_cfg.py
matthewtrepte Nov 21, 2025
9b55035
Adds --visualizer flag and updates behavior with --headless; also add…
kellyguo11 Nov 26, 2025
2c511b0
updates numpy to >=2
kellyguo11 Nov 26, 2025
3f77749
Remove carb settings and make SimulationApp optional in AppLauncher
kellyguo11 Nov 26, 2025
e0a16ff
adds new settings manager
kellyguo11 Nov 26, 2025
b76aeea
Renames carb settings
kellyguo11 Nov 27, 2025
9080acb
Merge branch 'dev/newton' of github.com:isaac-sim/IsaacLab into newto…
kellyguo11 Nov 27, 2025
6ad47b0
Update source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py
kellyguo11 Nov 27, 2025
89f621d
Update source/isaaclab/isaaclab/sim/simulation_cfg.py
kellyguo11 Nov 27, 2025
8ec7a12
Update source/isaaclab/isaaclab/visualizers/rerun_visualizer.py
kellyguo11 Nov 27, 2025
ec34aa6
Update source/isaaclab/isaaclab/visualizers/ov_visualizer.py
kellyguo11 Nov 27, 2025
3c5c27b
Merge branch 'newton/visualizers' of github.com:kellyguo11/IsaacLab-p…
kellyguo11 Nov 27, 2025
6345e9c
Merge branch 'dev/newton' of github.com:isaac-sim/IsaacLab into decou…
kellyguo11 Dec 1, 2025
70a686c
Merge branch 'dev/newton' of github.com:isaac-sim/IsaacLab into decou…
kellyguo11 Dec 1, 2025
5de0d38
Merge branch 'dev/newton' of github.com:isaac-sim/IsaacLab into decou…
kellyguo11 Dec 1, 2025
2323577
Hacks to remove kit dependencies
kellyguo11 Dec 2, 2025
a9fcb19
cartpole running without kit
ooctipus Dec 2, 2025
1fb981e
ov rendering somewhat working, ground plane materials not found
kellyguo11 Dec 2, 2025
c0b307d
comment out callback cleanup
kellyguo11 Dec 2, 2025
72df6af
add missing xform prim
kellyguo11 Dec 2, 2025
a96f4cc
format
kellyguo11 Dec 3, 2025
e7d268d
exit gracefully
kellyguo11 Dec 3, 2025
db315c9
Squashed commit of the following:
ooctipus Dec 4, 2025
588f670
add omni client fixes
ooctipus Dec 4, 2025
7aec53f
adapt new cloner
ooctipus Dec 4, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions isaaclab.sh
Original file line number Diff line number Diff line change
Expand Up @@ -348,6 +348,8 @@ while [[ $# -gt 0 ]]; do
# install the python packages in IsaacLab/source directory
echo "[INFO] Installing extensions inside the Isaac Lab repository..."
python_exe=$(extract_python_exe)
# install omni.client via packman helper
${python_exe} "${ISAACLAB_PATH}/tools/installation/install_omni_client_packman.py"
# check if pytorch is installed and its version
# install pytorch with cuda 12.8 for blackwell support
if ${python_exe} -m pip list 2>/dev/null | grep -q "torch"; then
Expand Down
319 changes: 319 additions & 0 deletions scripts/demos/cloner.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,319 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""This script demonstrates how to spawn multiple objects in multiple environments.

.. code-block:: bash

# Usage
./isaaclab.sh -p scripts/demos/multi_asset.py --num_envs 2048

"""

from __future__ import annotations

"""Launch Isaac Sim Simulator first."""


import argparse

from isaaclab.app import AppLauncher

# add argparse arguments
parser = argparse.ArgumentParser(description="Demo on spawning different objects in multiple environments.")
parser.add_argument("--num_envs", type=int, default=32, help="Number of environments to spawn.")
parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()

# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app

"""Rest everything follows."""

##
# Pre-defined Configuration
##
import torch

import isaaclab.sim as sim_utils
from isaaclab.assets import ( # RigidObject,; RigidObjectCfg,; RigidObjectCollection,; RigidObjectCollectionCfg,
Articulation,
ArticulationCfg,
AssetBaseCfg,
)
from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
from isaaclab.sim import SimulationContext
from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg
from isaaclab.sim._impl.solvers_cfg import MJWarpSolverCfg
from isaaclab.utils import Timer, configclass
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR

from isaaclab_assets.robots.anymal import ANYDRIVE_3_LSTM_ACTUATOR_CFG # isort: skip


##
# Scene Configuration
##


@configclass
class MultiObjectSceneCfg(InteractiveSceneCfg):
"""Configuration for a multi-object scene."""

# ground plane
ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())

# lights
dome_light = AssetBaseCfg(
prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
)

# rigid object
object: ArticulationCfg = ArticulationCfg(
prim_path="/World/envs/env_.*/Object",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd",
mass_props=sim_utils.MassPropertiesCfg(mass=25.0),
scale=(5.0, 5.0, 5.0),
rigid_props=sim_utils.RigidBodyPropertiesCfg(
solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
collision_props=sim_utils.CollisionPropertiesCfg(),
),
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)),
actuators={},
articulation_root_prim_path="",
)

# # object collection
# object_collection: RigidObjectCollectionCfg = RigidObjectCollectionCfg(
# rigid_objects={
# "object_A": RigidObjectCfg(
# prim_path="/World/envs/env_.*/Object_A",
# spawn=sim_utils.SphereCfg(
# radius=0.1,
# visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
# rigid_props=sim_utils.RigidBodyPropertiesCfg(
# solver_position_iteration_count=4, solver_velocity_iteration_count=0
# ),
# mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
# collision_props=sim_utils.CollisionPropertiesCfg(),
# ),
# init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, -0.5, 2.0)),
# ),
# "object_B": RigidObjectCfg(
# prim_path="/World/envs/env_.*/Object_B",
# spawn=sim_utils.CuboidCfg(
# size=(0.1, 0.1, 0.1),
# visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
# rigid_props=sim_utils.RigidBodyPropertiesCfg(
# solver_position_iteration_count=4, solver_velocity_iteration_count=0
# ),
# mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
# collision_props=sim_utils.CollisionPropertiesCfg(),
# ),
# init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.5, 2.0)),
# ),
# "object_C": RigidObjectCfg(
# prim_path="/World/envs/env_.*/Object_C",
# spawn=sim_utils.ConeCfg(
# radius=0.1,
# height=0.3,
# visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
# rigid_props=sim_utils.RigidBodyPropertiesCfg(
# solver_position_iteration_count=4, solver_velocity_iteration_count=0
# ),
# mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
# collision_props=sim_utils.CollisionPropertiesCfg(),
# ),
# init_state=RigidObjectCfg.InitialStateCfg(pos=(0.5, 0.0, 2.0)),
# ),
# }
# )

# # articulation
robot: ArticulationCfg = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd",
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
),
activate_contact_sensors=True,
),
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},
)

# articulation
# robot: ArticulationCfg = ArticulationCfg(
# prim_path="/World/envs/env_.*/Robot",
# spawn=sim_utils.MultiUsdFileCfg(
# usd_path=[
# f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd",
# f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd",
# ],
# random_choice=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
# ),
# activate_contact_sensors=True,
# ),
# 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},
# )


##
# Simulation Loop
##


def run_simulator(sim: SimulationContext, scene: InteractiveScene):
"""Runs the simulation loop."""
# Extract scene entities
# note: we only do this here for readability.
rigid_object: Articulation | None = scene["object"] if "object" in scene.keys() else None
rigid_object_collection: Articulation | None = (
scene["object_collection"] if "object_collection" in scene.keys() else None
)
robot: Articulation | None = scene["robot"] if "robot" in scene.keys() else None
# Define simulation stepping
sim_dt = sim.get_physics_dt()
count = 0
# Simulation loop
while simulation_app.is_running():
# Reset
if count % 250 == 0:
# reset counter
count = 0
# reset the scene entities
# object
if rigid_object:
root_state = rigid_object.data.default_root_state.clone()
root_state[:, :3] += scene.env_origins + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
rigid_object.write_root_pose_to_sim(root_state[:, :7])
rigid_object.write_root_velocity_to_sim(root_state[:, 7:])
# object collection
if rigid_object_collection:
object_state = rigid_object_collection.data.default_object_state.clone()
object_state[..., :3] += (
scene.env_origins.unsqueeze(1) + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
)
rigid_object_collection.write_object_link_pose_to_sim(object_state[..., :7])
rigid_object_collection.write_object_com_velocity_to_sim(object_state[..., 7:])
# robot
if robot:
# -- root state
root_state = robot.data.default_root_state.clone()
root_state[:, :3] += scene.env_origins + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
robot.write_root_pose_to_sim(root_state[:, :7])
robot.write_root_velocity_to_sim(root_state[:, 7:])
# -- joint state
joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone()
robot.write_joint_state_to_sim(joint_pos, joint_vel)
# clear internal buffers
scene.reset()
print("[INFO]: Resetting scene state...")

# Apply action to robot
# robot.set_joint_position_target(robot.data.default_joint_pos)
# Write data to sim
scene.write_data_to_sim()
# Perform step
sim.step()
# Increment counter
count += 1
# Update buffers
scene.update(sim_dt)


def main():
"""Main function."""
# Load kit helper

newton_cfg = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=300,
nconmax=25,
ls_iterations=15,
cone="elliptic",
impratio=100.0,
ls_parallel=True,
),
num_substeps=1,
debug_mode=False,
)
sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, newton_cfg=newton_cfg)
sim_cfg.enable_newton_rendering = args_cli.newton_visualizer
sim = SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
# Design scene
scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=True)
with Timer("[INFO] Time to create scene: "):
scene = InteractiveScene(scene_cfg)

# with Timer("[INFO] Time to randomize scene: "):
# # DO YOUR OWN OTHER KIND OF RANDOMIZATION HERE!
# # Note: Just need to acquire the right attribute about the property you want to set
# # Here is an example on setting color randomly
# randomize_shape_color(scene_cfg.object.prim_path)

# Play the simulator
with Timer("[INFO] Time to start Simulation: "):
# The code `sim.reset()` is resetting a simulation or a simulation environment.
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, scene)


if __name__ == "__main__":
# run the main execution
main()
# close sim app
simulation_app.close()
2 changes: 2 additions & 0 deletions source/isaaclab/isaaclab/app/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,9 @@

* Ability to launch the simulation app with different configurations
* Run tests with the simulation app
* Settings manager for storing configuration in both Omniverse and standalone modes

"""

from .app_launcher import AppLauncher # noqa: F401, F403
from .settings_manager import SettingsManager, get_settings_manager, initialize_carb_settings # noqa: F401, F403
Loading
Loading