Skip to content

Commit 1894583

Browse files
authored
Merge branch 'main' into main
2 parents 3d7d097 + e956ddb commit 1894583

File tree

11 files changed

+71
-26
lines changed

11 files changed

+71
-26
lines changed

.pre-commit-config.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ repos:
4545
- id: codespell
4646
additional_dependencies:
4747
- tomli
48+
exclude: "CONTRIBUTORS.md"
4849
# FIXME: Figure out why this is getting stuck under VPN.
4950
# - repo: https://github.com/RobertCraigie/pyright-python
5051
# rev: v1.1.315

CONTRIBUTORS.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,7 @@ Guidelines for modifications:
6262
* Lionel Gulich
6363
* Louis Le Lay
6464
* Lorenz Wellhausen
65+
* Manuel Schweiger
6566
* Masoud Moghani
6667
* Michael Gussert
6768
* Michael Noseworthy

docs/source/overview/core-concepts/actuators.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ maximum effort:
3434

3535
.. math::
3636
37-
\tau_{j, computed} & = k_p * (q - q_{des}) + k_d * (\dot{q} - \dot{q}_{des}) + \tau_{ff} \\
37+
\tau_{j, computed} & = k_p * (q_{des} - q) + k_d * (\dot{q}_{des} - \dot{q}) + \tau_{ff} \\
3838
\tau_{j, applied} & = clip(\tau_{computed}, -\tau_{j, max}, \tau_{j, max})
3939
4040

source/extensions/omni.isaac.lab/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.30.3"
4+
version = "0.30.4"
55

66
# Description
77
title = "Isaac Lab framework for Robot Learning"

source/extensions/omni.isaac.lab/docs/CHANGELOG.rst

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,16 @@
11
Changelog
22
---------
33

4+
0.30.4 (2025-01-08)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Fixed
8+
^^^^^
9+
10+
* fixed docstring in articulation data :class:`omni.isaac.lab.assets.ArticulationData`.
11+
In body properties sections, the second dimension should be num_bodies but was documented as 1.
12+
13+
414
0.30.3 (2025-01-02)
515
~~~~~~~~~~~~~~~~~~~
616

source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation.py

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -385,11 +385,13 @@ def write_root_com_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[
385385
env_ids: Environment indices. If None, then all indices are used.
386386
"""
387387
# resolve all indices
388+
physx_env_ids = env_ids
388389
if env_ids is None:
389-
local_env_ids = slice(None)
390+
env_ids = slice(None)
391+
physx_env_ids = self._ALL_INDICES
390392

391-
com_pos = self.data.com_pos_b[local_env_ids, 0, :]
392-
com_quat = self.data.com_quat_b[local_env_ids, 0, :]
393+
com_pos = self.data.com_pos_b[env_ids, 0, :]
394+
com_quat = self.data.com_quat_b[env_ids, 0, :]
393395

394396
root_link_pos, root_link_quat = math_utils.combine_frame_transforms(
395397
root_pose[..., :3],
@@ -399,7 +401,7 @@ def write_root_com_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[
399401
)
400402

401403
root_link_pose = torch.cat((root_link_pos, root_link_quat), dim=-1)
402-
self.write_root_link_pose_to_sim(root_pose=root_link_pose, env_ids=env_ids)
404+
self.write_root_link_pose_to_sim(root_pose=root_link_pose, env_ids=physx_env_ids)
403405

404406
def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
405407
"""Set the root center of mass velocity over selected environment indices into the simulation.
@@ -458,18 +460,20 @@ def write_root_link_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids:
458460
env_ids: Environment indices. If None, then all indices are used.
459461
"""
460462
# resolve all indices
463+
physx_env_ids = env_ids
461464
if env_ids is None:
462-
local_env_ids = slice(None)
465+
env_ids = slice(None)
466+
physx_env_ids = self._ALL_INDICES
463467

464468
root_com_velocity = root_velocity.clone()
465-
quat = self.data.root_link_state_w[local_env_ids, 3:7]
466-
com_pos_b = self.data.com_pos_b[local_env_ids, 0, :]
469+
quat = self.data.root_link_state_w[env_ids, 3:7]
470+
com_pos_b = self.data.com_pos_b[env_ids, 0, :]
467471
# transform given velocity to center of mass
468472
root_com_velocity[:, :3] += torch.linalg.cross(
469473
root_com_velocity[:, 3:], math_utils.quat_rotate(quat, com_pos_b), dim=-1
470474
)
471475
# write center of mass velocity to sim
472-
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity, env_ids=env_ids)
476+
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity, env_ids=physx_env_ids)
473477

474478
def write_joint_state_to_sim(
475479
self,

source/extensions/omni.isaac.lab/omni/isaac/lab/assets/articulation/articulation_data.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -747,7 +747,7 @@ def body_ang_acc_w(self) -> torch.Tensor:
747747

748748
@property
749749
def body_link_pos_w(self) -> torch.Tensor:
750-
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
750+
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
751751
752752
This quantity is the position of the rigid bodies' actor frame relative to the world.
753753
"""
@@ -760,7 +760,7 @@ def body_link_pos_w(self) -> torch.Tensor:
760760

761761
@property
762762
def body_link_quat_w(self) -> torch.Tensor:
763-
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, 1, 4).
763+
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).
764764
765765
This quantity is the orientation of the rigid bodies' actor frame relative to the world.
766766
"""
@@ -774,7 +774,7 @@ def body_link_quat_w(self) -> torch.Tensor:
774774

775775
@property
776776
def body_link_vel_w(self) -> torch.Tensor:
777-
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6).
777+
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).
778778
779779
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame
780780
relative to the world.
@@ -783,15 +783,15 @@ def body_link_vel_w(self) -> torch.Tensor:
783783

784784
@property
785785
def body_link_lin_vel_w(self) -> torch.Tensor:
786-
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
786+
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
787787
788788
This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
789789
"""
790790
return self.body_link_state_w[..., 7:10]
791791

792792
@property
793793
def body_link_ang_vel_w(self) -> torch.Tensor:
794-
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
794+
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
795795
796796
This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
797797
"""
@@ -803,7 +803,7 @@ def body_link_ang_vel_w(self) -> torch.Tensor:
803803

804804
@property
805805
def body_com_pos_w(self) -> torch.Tensor:
806-
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
806+
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
807807
808808
This quantity is the position of the rigid bodies' actor frame.
809809
"""
@@ -813,13 +813,13 @@ def body_com_pos_w(self) -> torch.Tensor:
813813
def body_com_quat_w(self) -> torch.Tensor:
814814
"""Orientation (w, x, y, z) of the prinicple axies of inertia of all bodies in simulation world frame.
815815
816-
Shape is (num_instances, 1, 4). This quantity is the orientation of the rigid bodies' actor frame.
816+
Shape is (num_instances, num_bodies, 4). This quantity is the orientation of the rigid bodies' actor frame.
817817
"""
818818
return self.body_com_state_w[..., 3:7]
819819

820820
@property
821821
def body_com_vel_w(self) -> torch.Tensor:
822-
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6).
822+
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).
823823
824824
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
825825
"""
@@ -832,7 +832,7 @@ def body_com_vel_w(self) -> torch.Tensor:
832832

833833
@property
834834
def body_com_lin_vel_w(self) -> torch.Tensor:
835-
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
835+
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
836836
837837
This quantity is the linear velocity of the rigid bodies' center of mass frame.
838838
"""
@@ -845,7 +845,7 @@ def body_com_lin_vel_w(self) -> torch.Tensor:
845845

846846
@property
847847
def body_com_ang_vel_w(self) -> torch.Tensor:
848-
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
848+
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
849849
850850
This quantity is the angular velocity of the rigid bodies' center of mass frame.
851851
"""

source/extensions/omni.isaac.lab/test/assets/test_articulation.py

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1088,6 +1088,7 @@ def test_write_root_state(self):
10881088
# make quaternion a unit vector
10891089
rand_state[..., 3:7] = torch.nn.functional.normalize(rand_state[..., 3:7], dim=-1)
10901090

1091+
env_idx = env_idx.to(device)
10911092
for i in range(10):
10921093

10931094
# perform step
@@ -1096,9 +1097,15 @@ def test_write_root_state(self):
10961097
articulation.update(sim.cfg.dt)
10971098

10981099
if state_location == "com":
1099-
articulation.write_root_com_state_to_sim(rand_state)
1100+
if i % 2 == 0:
1101+
articulation.write_root_com_state_to_sim(rand_state)
1102+
else:
1103+
articulation.write_root_com_state_to_sim(rand_state, env_ids=env_idx)
11001104
elif state_location == "link":
1101-
articulation.write_root_link_state_to_sim(rand_state)
1105+
if i % 2 == 0:
1106+
articulation.write_root_link_state_to_sim(rand_state)
1107+
else:
1108+
articulation.write_root_link_state_to_sim(rand_state, env_ids=env_idx)
11021109

11031110
if state_location == "com":
11041111
torch.testing.assert_close(rand_state, articulation.data.root_com_state_w)

source/extensions/omni.isaac.lab/test/utils/test_configclass.py

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -143,6 +143,16 @@ class BasicDemoTorchCfg:
143143
some_tensor: torch.Tensor = torch.Tensor([1, 2, 3])
144144

145145

146+
@configclass
147+
class BasicActuatorCfg:
148+
"""Dummy configuration class for ActuatorBase config."""
149+
150+
joint_names_expr: list[str] = ["some_string"]
151+
joint_parameter_lookup: list[list[float]] = [[1, 2, 3], [4, 5, 6]]
152+
stiffness: float = 1.0
153+
damping: float = 2.0
154+
155+
146156
"""
147157
Dummy configuration to check type annotations ordering.
148158
"""
@@ -530,6 +540,18 @@ def test_dict_conversion(self):
530540
self.assertEqual(torch_cfg_dict["some_number"], 0)
531541
self.assertTrue(torch.all(torch_cfg_dict["some_tensor"] == torch.tensor([1, 2, 3])))
532542

543+
def test_actuator_cfg_dict_conversion(self):
544+
"""Test dict conversion of ActuatorConfig."""
545+
# create a basic RemotizedPDActuator config
546+
actuator_cfg = BasicActuatorCfg()
547+
# return writable attributes of config object
548+
actuator_cfg_dict_attr = actuator_cfg.__dict__
549+
# check if __dict__ attribute of config is not empty
550+
self.assertTrue(len(actuator_cfg_dict_attr) > 0)
551+
# class_to_dict utility function should return a primitive dictionary
552+
actuator_cfg_dict = class_to_dict(actuator_cfg)
553+
self.assertTrue(isinstance(actuator_cfg_dict, dict))
554+
533555
def test_dict_conversion_order(self):
534556
"""Tests that order is conserved when converting to dictionary."""
535557
true_outer_order = ["device_id", "env", "robot_default_state", "list_config"]

source/standalone/tools/check_instanceable.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -82,12 +82,12 @@ def main():
8282
sim = SimulationContext(
8383
stage_units_in_meters=1.0, physics_dt=0.01, rendering_dt=0.01, backend="torch", device="cuda:0"
8484
)
85-
# enable flatcache which avoids passing data over to USD structure
85+
# enable fabric which avoids passing data over to USD structure
8686
# this speeds up the read-write operation of GPU buffers
8787
if sim.get_physics_context().use_gpu_pipeline:
88-
sim.get_physics_context().enable_flatcache(True)
88+
sim.get_physics_context().enable_fabric(True)
8989
# enable hydra scene-graph instancing
90-
# this is needed to visualize the scene when flatcache is enabled
90+
# this is needed to visualize the scene when fabric is enabled
9191
set_carb_setting(sim._settings, "/persistent/omnihydra/useSceneGraphInstancing", True)
9292

9393
# Create interface to clone the scene

0 commit comments

Comments
 (0)