Skip to content

Commit c3220cb

Browse files
committed
Merge remote-tracking branch 'origin/dev/newton' into milad/friction-randomization
2 parents 6d69d71 + d5cb6ce commit c3220cb

File tree

94 files changed

+7273
-37
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

94 files changed

+7273
-37
lines changed

scripts/benchmarks/eval_all_for_newton_alpha_for_scaling.sh

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
ISAAC_EXEC_SCRIPT=/home/antoiner/Documents/IsaacLab-Internal/isaaclab.sh
44
RSL_SCRIPT=scripts/benchmarks/benchmark_non_rl.py
5-
TASKS="Isaac-Cartpole-Direct-v0 Isaac-Ant-Direct-v0 Isaac-Humanoid-Direct-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-H1-v0"
5+
TASKS="Isaac-Repose-Cube-Allegro-Direct-v0 Isaac-Ant-Direct-v0 Isaac-Cartpole-Direct-v0 Isaac-Cartpole-RGB-Camera-Direct-v0 Isaac-Cartpole-Depth-Camera-Direct-v0 Isaac-Humanoid-Direct-v0 Isaac-Ant-v0 Isaac-Cartpole-v0 Isaac-Humanoid-v0 Isaac-Velocity-Flat-Unitree-A1-v0 Isaac-Velocity-Flat-Anymal-B-v0 Isaac-Velocity-Flat-Anymal-C-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-Cassie-v0 Isaac-Velocity-Flat-G1-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-Unitree-Go1-v0 Isaac-Velocity-Flat-Unitree-Go2-v0 Isaac-Velocity-Flat-H1-v0 Isaac-Velocity-Flat-Spot-v0 Isaac-Reach-Franka-v0 Isaac-Reach-UR10-v0"
66
NUM_FRAMES=100
77
NUM_ENVS="1024 2048 4096 8192 16384"
88
TARGET_FOLDER=$1
@@ -11,6 +11,10 @@ for task in $TASKS
1111
do
1212
for num_envs in $NUM_ENVS
1313
do
14-
$ISAAC_EXEC_SCRIPT -p $RSL_SCRIPT --task $task --num_frames $NUM_FRAMES --headless --num_envs $num_envs --output_folder $TARGET_FOLDER
14+
if [[ $task == *"RGB-Camera"* ]] || [[ $task == *"Depth-Camera"* ]]; then
15+
$ISAAC_EXEC_SCRIPT -p $RSL_SCRIPT --task $task --num_frames $NUM_FRAMES --headless --num_envs $num_envs --output_folder $TARGET_FOLDER --enable_cameras
16+
else
17+
$ISAAC_EXEC_SCRIPT -p $RSL_SCRIPT --task $task --num_frames $NUM_FRAMES --headless --num_envs $num_envs --output_folder $TARGET_FOLDER
18+
fi
1519
done
1620
done

source/isaaclab/isaaclab/assets/articulation/articulation.py

Lines changed: 22 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,7 @@ def write_data_to_sim(self):
202202
"""
203203
# write external wrench
204204
if self.has_external_wrench:
205-
wrenches_b = torch.cat([self._external_force_b, self._external_force_b], dim=-1)
205+
wrenches_b = torch.cat([self._external_force_b, self._external_torque_b], dim=-1)
206206
self._root_newton_view.set_attribute("body_f", NewtonManager.get_state_0(), wp.from_torch(wrenches_b))
207207

208208
# apply actuator models
@@ -1374,6 +1374,15 @@ def _initialize_impl(self):
13741374
# log joint information
13751375
self._log_articulation_info()
13761376

1377+
# Moves the articulation to its default pose before the solver is initialized
1378+
generated_pose = self._data.default_root_state[:, :7].clone()
1379+
generated_pose[:, 3:] = math_utils.convert_quat(generated_pose[:, 3:], to="xyzw")
1380+
generated_pose[:, :2] += wp.to_torch(self._root_newton_view.get_root_transforms(NewtonManager.get_model()))[
1381+
:, :2
1382+
]
1383+
self._root_newton_view.set_root_transforms(NewtonManager.get_state_0(), generated_pose)
1384+
self._root_newton_view.set_root_transforms(NewtonManager.get_model(), generated_pose)
1385+
13771386
def _create_buffers(self):
13781387
# constants
13791388
self._ALL_INDICES = torch.arange(self.num_instances, dtype=torch.long, device=self.device)
@@ -1479,17 +1488,19 @@ def _process_cfg(self):
14791488
# -- joint state
14801489
self._data.default_joint_pos = torch.zeros(self.num_instances, self.num_joints, device=self.device)
14811490
self._data.default_joint_vel = torch.zeros_like(self._data.default_joint_pos)
1482-
# joint pos
1483-
indices_list, _, values_list = string_utils.resolve_matching_names_values(
1484-
self.cfg.init_state.joint_pos, self.joint_names
1485-
)
1486-
self._data.default_joint_pos[:, indices_list] = torch.tensor(values_list, device=self.device)
14871491

1488-
# joint vel
1489-
indices_list, _, values_list = string_utils.resolve_matching_names_values(
1490-
self.cfg.init_state.joint_vel, self.joint_names
1491-
)
1492-
self._data.default_joint_vel[:, indices_list] = torch.tensor(values_list, device=self.device)
1492+
if self.num_joints > 0:
1493+
# joint pos
1494+
indices_list, _, values_list = string_utils.resolve_matching_names_values(
1495+
self.cfg.init_state.joint_pos, self.joint_names
1496+
)
1497+
self._data.default_joint_pos[:, indices_list] = torch.tensor(values_list, device=self.device)
1498+
1499+
# joint vel
1500+
indices_list, _, values_list = string_utils.resolve_matching_names_values(
1501+
self.cfg.init_state.joint_vel, self.joint_names
1502+
)
1503+
self._data.default_joint_vel[:, indices_list] = torch.tensor(values_list, device=self.device)
14931504

14941505
"""
14951506
Internal simulation callbacks.

source/isaaclab/isaaclab/assets/articulation/articulation_data.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -491,13 +491,13 @@ def root_com_vel_w(self) -> torch.Tensor:
491491
relative to the world.
492492
"""
493493
if self._root_com_vel_w.timestamp < self._sim_timestamp:
494-
# Newton reads velocities as [wx, wy, wz, vx, vy, vz] Isaac reads as [vx, vy, vz, wx, wy, wz]
494+
# Newton and Isaac: [vx, vy, vz, wx, wy, wz]
495495
velocity = self._root_newton_view.get_root_velocities(NewtonManager.get_state_0())
496496
if velocity is None:
497497
velocity = torch.zeros((self._root_newton_view.count, 6), device=self.device)
498498
else:
499499
velocity = wp.to_torch(velocity).clone()
500-
self._root_com_vel_w.data = torch.cat((velocity[:, 3:], velocity[:, :3]), dim=-1)
500+
self._root_com_vel_w.data = velocity
501501
self._root_com_vel_w.timestamp = self._sim_timestamp
502502

503503
return self._root_com_vel_w.data

source/isaaclab/isaaclab/cloner/utils.py

Lines changed: 29 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
import warp as wp
1010
from newton import AxisType, ModelBuilder
11+
from pxr import Usd
1112

1213
from isaaclab.utils.timer import Timer
1314

@@ -58,14 +59,35 @@ def replicate_environment(
5859
print(f"WARNING: up_axis '{up_axis}' does not match USD stage up_axis '{stage_up_axis}'")
5960

6061
with Timer(name="newton_prototype_builder", msg="Prototype Builder took:", enable=True, format="ms"):
61-
# load just the prototype env
62+
# Get child xforms from the prototype path
63+
child_xforms = []
64+
if isinstance(source, str):
65+
# If source is a file path, load the stage
66+
stage = Usd.Stage.Open(source)
67+
else:
68+
# If source is already a stage
69+
stage = source
70+
71+
# Get the prototype prim
72+
prototype_prim = stage.GetPrimAtPath(prototype_path)
73+
if prototype_prim.IsValid():
74+
# Get all child prims that are Xforms
75+
for child_prim in prototype_prim.GetAllChildren():
76+
if child_prim.GetTypeName() == "Xform":
77+
child_xforms.append(child_prim.GetPath().pathString)
78+
79+
# If no child xforms found, use the prototype path itself
80+
if not child_xforms:
81+
child_xforms = [prototype_path]
82+
6283
prototype_builder = ModelBuilder(up_axis=up_axis)
63-
prototype_builder.add_usd(
64-
source,
65-
root_path=prototype_path,
66-
load_non_physics_prims=False,
67-
**usd_kwargs,
68-
)
84+
for child_path in child_xforms:
85+
prototype_builder.add_usd(
86+
source,
87+
root_path=child_path,
88+
load_non_physics_prims=False,
89+
**usd_kwargs,
90+
)
6991
prototype_builder.approximate_meshes("convex_hull")
7092

7193
with Timer(name="newton_multiple_add_to_builder", msg="All add to builder took:", enable=True, format="ms"):

source/isaaclab/isaaclab/sensors/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
3636
"""
3737

38+
from .camera import * # noqa: F401, F403
3839
from .contact_sensor import * # noqa: F401, F403
3940
from .sensor_base import SensorBase # noqa: F401
4041
from .sensor_base_cfg import SensorBaseCfg # noqa: F401
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
"""Sub-module for camera wrapper around USD camera prim."""
7+
8+
from .camera import Camera
9+
from .camera_cfg import CameraCfg
10+
from .camera_data import CameraData
11+
from .tiled_camera import TiledCamera
12+
from .tiled_camera_cfg import TiledCameraCfg
13+
from .utils import * # noqa: F401, F403

0 commit comments

Comments
 (0)