Skip to content

Commit 999c1e9

Browse files
Removes deprecation for root_state_w properties and setters (#1695)
…ection root and base states # Description <!-- Thank you for your interest in sending a pull request. Please make sure to check the contribution guidelines. Link: https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html --> This PR removes the deprecation of root_state_w setters and properties due to significant regression in training speed. It leaves it the root_link_* and root_com_* properties and setters but does not force them on examples and tests. Fixes #1699 <!-- As a practice, it is recommended to open an issue to have discussions on the proposed pull request. This makes it easier for the community to keep track of what is being developed or added, and if a given feature is demanded by more than one party. --> ## Type of change <!-- As you go through the list, delete the ones that are not applicable. --> - Bug fix (non-breaking change which fixes an issue) <!-- Example: | Before | After | | ------ | ----- | | _gif/png before_ | _gif/png after_ | To upload images to a PR -- simply drag and drop an image while in edit mode and it should upload the image directly. You can then paste that source into the above before/after sections. --> ## Checklist - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there <!-- As you go through the checklist above, you can mark something as done by putting an x character in it For example, - [x] I have done this task - [ ] I have not done this task --> --------- Signed-off-by: James Tigue <[email protected]> Co-authored-by: Kelly Guo <[email protected]> Co-authored-by: Kelly Guo <[email protected]>
1 parent 7ed94ce commit 999c1e9

File tree

88 files changed

+533
-579
lines changed

Some content is hidden

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

88 files changed

+533
-579
lines changed

docs/source/migration/migrating_from_isaacgymenvs.rst

+2-2
Original file line numberDiff line numberDiff line change
@@ -814,9 +814,9 @@ The ``progress_buf`` variable has also been renamed to ``episode_length_buf``.
814814
| | |
815815
| | self.joint_pos[env_ids] = joint_pos |
816816
| | |
817-
| | self.cartpole.write_root_link_pose_to_sim( |
817+
| | self.cartpole.write_root_pose_to_sim( |
818818
| | default_root_state[:, :7], env_ids) |
819-
| | self.cartpole.write_root_com_velocity_to_sim( |
819+
| | self.cartpole.write_root_velocity_to_sim( |
820820
| | default_root_state[:, 7:], env_ids) |
821821
| | self.cartpole.write_joint_state_to_sim( |
822822
| | joint_pos, joint_vel, None, env_ids) |

docs/source/migration/migrating_from_omniisaacgymenvs.rst

+4-4
Original file line numberDiff line numberDiff line change
@@ -364,8 +364,8 @@ In Isaac Lab, ``root_pose`` and ``root_velocity`` have been combined into single
364364

365365
.. code-block::python
366366
367-
self.cartpole.write_root_link_pose_to_sim(default_root_state[:, :7], env_ids)
368-
self.cartpole.write_root_com_velocity_to_sim(default_root_state[:, 7:], env_ids)
367+
self.cartpole.write_root_pose_to_sim(default_root_state[:, :7], env_ids)
368+
self.cartpole.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids)
369369
370370
371371
Creating a New Environment
@@ -738,9 +738,9 @@ reset the ``episode_length_buf`` buffer.
738738
| 1.0 - 2.0 * torch.rand(num_resets, device=self._device)) | self.joint_pos[env_ids] = joint_pos |
739739
| | self.joint_vel[env_ids] = joint_vel |
740740
| # apply resets | |
741-
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_link_pose_to_sim( |
741+
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_pose_to_sim( |
742742
| self._cartpoles.set_joint_positions(dof_pos, indices=indices) | default_root_state[:, :7], env_ids) |
743-
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_com_velocity_to_sim( |
743+
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_velocity_to_sim( |
744744
| | default_root_state[:, 7:], env_ids) |
745745
| # bookkeeping | self.cartpole.write_joint_state_to_sim( |
746746
| self.reset_buf[env_ids] = 0 | joint_pos, joint_vel, None, env_ids) |

docs/source/tutorials/01_assets/run_articulation.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ Similar to a rigid object, an articulation also has a root state. This state cor
6666
articulation tree. On top of the root state, an articulation also has joint states. These states correspond to the
6767
joint positions and velocities.
6868

69-
To reset the articulation, we first set the root state by calling the :meth:`Articulation.write_root_link_pose_to_sim` and :meth:`Articulation.write_root_com_velocity_to_sim`
69+
To reset the articulation, we first set the root state by calling the :meth:`Articulation.write_root_pose_to_sim` and :meth:`Articulation.write_root_velocity_to_sim`
7070
methods. Similarly, we set the joint states by calling the :meth:`Articulation.write_joint_state_to_sim` method.
7171
Finally, we call the :meth:`Articulation.reset` method to reset any internal buffers and caches.
7272

docs/source/tutorials/01_assets/run_deformable_object.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,7 @@ the average position of all the nodes in the mesh.
149149
.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_deformable_object.py
150150
:language: python
151151
:start-at: # update buffers
152-
:end-at: print(f"Root position (in world): {cube_object.data.root_link_pos_w[:, :3]}")
152+
:end-at: print(f"Root position (in world): {cube_object.data.root_pos_w[:, :3]}")
153153

154154

155155
The Code Execution

docs/source/tutorials/01_assets/run_rigid_object.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ desired state of the rigid object prim into the world frame before setting it.
9696
We use the :attr:`assets.RigidObject.data.default_root_state` attribute to get the default root state of the
9797
spawned rigid object prims. This default state can be configured from the :attr:`assets.RigidObjectCfg.init_state`
9898
attribute, which we left as identity in this tutorial. We then randomize the translation of the root state and
99-
set the desired state of the rigid object prim using the :meth:`assets.RigidObject.write_root_link_pose_to_sim` and :meth:`assets.RigidObject.write_root_com_velocity_to_sim` methods.
99+
set the desired state of the rigid object prim using the :meth:`assets.RigidObject.write_root_pose_to_sim` and :meth:`assets.RigidObject.write_root_velocity_to_sim` methods.
100100
As the name suggests, this method writes the root state of the rigid object prim into the simulation buffer.
101101

102102
.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_rigid_object.py

docs/source/tutorials/05_controllers/run_diff_ik.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ joint positions, current end-effector pose, and the Jacobian matrix.
7979

8080
While the attribute :attr:`assets.ArticulationData.joint_pos` provides the joint positions,
8181
we only want the joint positions of the robot's arm, and not the gripper. Similarly, while
82-
the attribute :attr:`assets.ArticulationData.body_link_state_w` provides the state of all the
82+
the attribute :attr:`assets.Articulationdata.body_state_w` provides the state of all the
8383
robot's bodies, we only want the state of the robot's end-effector. Thus, we need to
8484
index into these arrays to obtain the desired quantities.
8585

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

+1-1
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.5"
4+
version = "0.30.6"
55

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

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

+29
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,35 @@
11
Changelog
22
---------
33

4+
0.30.6 (2025-01-17)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Fixed
8+
^^^^^
9+
10+
* removed deprecation of :attr:`omni.isaac.lab.assets.ArticulationData.root_state_w` and
11+
:attr:`omni.isaac.lab.assets.ArticulationData.body_state_w` derived properties.
12+
* removed deprecation of :meth:`omni.isaac.lab.assets.Articulation.write_root_state_to_sim`.
13+
* replaced calls to :attr:`omni.isaac.lab.assets.ArticulationData.root_com_state_w` and
14+
:attr:`omni.isaac.lab.assets.ArticulationData.root_link_state_w` with corresponding calls to
15+
:attr:`omni.isaac.lab.assets.ArticulationData.root_state_w`.
16+
* replaced calls to :attr:`omni.isaac.lab.assets.ArticulationData.body_com_state_w` and
17+
:attr:`omni.isaac.lab.assets.ArticulationData.body_link_state_w` properties with corresponding calls to
18+
:attr:`omni.isaac.lab.assets.ArticulationData.body_state_w` properties.
19+
* removed deprecation of :attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` derived properties .
20+
* removed deprecation of :meth:`omni.isaac.lab.assets.RigidObject.write_root_state_to_sim`.
21+
* replaced calls to :attr:`omni.isaac.lab.assets.RigidObjectData.root_com_state_w` and
22+
:attr:`omni.isaac.lab.assets.RigidObjectData.root_link_state_w` properties with corresponding calls to
23+
:attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` properties.
24+
* removed deprecation of :attr:`omni.isaac.lab.assets.RigidObjectCollectionData.root_state_w` derived properties.
25+
* removed deprecation of :meth:`omni.isaac.lab.assets.RigidObjectCollection.write_root_state_to_sim`.
26+
* replaced calls to :attr:`omni.isaac.lab.assets.RigidObjectCollectionData.root_com_state_w` and
27+
:attr:`omni.isaac.lab.assets.RigidObjectData.root_link_state_w` properties with corresponding calls to
28+
:attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` properties.
29+
* fixed indexing issue in ``write_root_link_velocity_to_sim`` in :class:`omni.isaac.lab.assets.RigidObject`
30+
* fixed index broadcasting in ``write_object_link_velocity_to_sim`` and ``write_object_com_pose_to_sim`` in :class:`omni.isaac.lab.assets.RigidObjectCollection`
31+
32+
433
0.30.5 (2025-01-14)
534
~~~~~~~~~~~~~~~~~~~
635

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

+28-36
Original file line numberDiff line numberDiff line change
@@ -98,10 +98,6 @@ def __init__(self, cfg: ArticulationCfg):
9898
"""
9999
super().__init__(cfg)
100100

101-
self._root_state_dep_warn = False
102-
self._root_pose_dep_warn = False
103-
self._root_vel_dep_warn = False
104-
105101
"""
106102
Properties
107103
"""
@@ -285,14 +281,6 @@ def write_root_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[in
285281
env_ids: Environment indices. If None, then all indices are used.
286282
"""
287283

288-
# deprecation warning
289-
if not self._root_state_dep_warn:
290-
omni.log.warn(
291-
"DeprecationWarning: Articluation.write_root_state_to_sim will be removed in a future release. Please"
292-
" use write_root_link_state_to_sim or write_root_com_state_to_sim instead."
293-
)
294-
self._root_state_dep_warn = True
295-
296284
# set into simulation
297285
self.write_root_pose_to_sim(root_state[:, :7], env_ids=env_ids)
298286
self.write_root_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
@@ -334,15 +322,21 @@ def write_root_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int]
334322
root_pose: Root poses in simulation frame. Shape is (len(env_ids), 7).
335323
env_ids: Environment indices. If None, then all indices are used.
336324
"""
337-
# deprecation warning
338-
if not self._root_pose_dep_warn:
339-
omni.log.warn(
340-
"DeprecationWarning: Articluation.write_root_pos_to_sim will be removed in a future release. Please use"
341-
" write_root_link_pose_to_sim or write_root_com_pose_to_sim instead."
342-
)
343-
self._root_pose_dep_warn = True
344-
345-
self.write_root_link_pose_to_sim(root_pose, env_ids)
325+
# resolve all indices
326+
physx_env_ids = env_ids
327+
if env_ids is None:
328+
env_ids = slice(None)
329+
physx_env_ids = self._ALL_INDICES
330+
# note: we need to do this here since tensors are not set into simulation until step.
331+
# set into internal buffers
332+
self._data.root_state_w[env_ids, :7] = root_pose.clone()
333+
# convert root quaternion from wxyz to xyzw
334+
root_poses_xyzw = self._data.root_state_w[:, :7].clone()
335+
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
336+
# Need to invalidate the buffer to trigger the update with the new root pose.
337+
self._data._body_state_w.timestamp = -1.0
338+
# set into simulation
339+
self.root_physx_view.set_root_transforms(root_poses_xyzw, indices=physx_env_ids)
346340

347341
def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None):
348342
"""Set the root link pose over selected environment indices into the simulation.
@@ -361,9 +355,7 @@ def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence
361355
# note: we need to do this here since tensors are not set into simulation until step.
362356
# set into internal buffers
363357
self._data.root_link_state_w[env_ids, :7] = root_pose.clone()
364-
self._data._ignore_dep_warn = True
365358
self._data.root_state_w[env_ids, :7] = self._data.root_link_state_w[env_ids, :7]
366-
self._data._ignore_dep_warn = False
367359
# convert root quaternion from wxyz to xyzw
368360
root_poses_xyzw = self._data.root_link_state_w[:, :7].clone()
369361
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
@@ -413,15 +405,17 @@ def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Seque
413405
root_velocity: Root center of mass velocities in simulation world frame. Shape is (len(env_ids), 6).
414406
env_ids: Environment indices. If None, then all indices are used.
415407
"""
416-
# deprecation warning
417-
if not self._root_vel_dep_warn:
418-
omni.log.warn(
419-
"DeprecationWarning: Articluation.write_root_velocity_to_sim will be removed in a future release."
420-
" Please use write_root_link_velocity_to_sim or write_root_com_velocity_to_sim instead."
421-
)
422-
self._root_vel_dep_warn = True
423-
424-
self.write_root_com_velocity_to_sim(root_velocity=root_velocity, env_ids=env_ids)
408+
# resolve all indices
409+
physx_env_ids = env_ids
410+
if env_ids is None:
411+
env_ids = slice(None)
412+
physx_env_ids = self._ALL_INDICES
413+
# note: we need to do this here since tensors are not set into simulation until step.
414+
# set into internal buffers
415+
self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
416+
self._data.body_acc_w[env_ids] = 0.0
417+
# set into simulation
418+
self.root_physx_view.set_root_velocities(self._data.root_state_w[:, 7:], indices=physx_env_ids)
425419

426420
def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
427421
"""Set the root center of mass velocity over selected environment indices into the simulation.
@@ -442,9 +436,7 @@ def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: S
442436
# note: we need to do this here since tensors are not set into simulation until step.
443437
# set into internal buffers
444438
self._data.root_com_state_w[env_ids, 7:] = root_velocity.clone()
445-
self._data._ignore_dep_warn = True
446439
self._data.root_state_w[env_ids, 7:] = self._data.root_com_state_w[env_ids, 7:]
447-
self._data._ignore_dep_warn = False
448440
self._data.body_acc_w[env_ids] = 0.0
449441
# set into simulation
450442
self.root_physx_view.set_root_velocities(self._data.root_com_state_w[:, 7:], indices=physx_env_ids)
@@ -507,8 +499,8 @@ def write_joint_state_to_sim(
507499
self._data.joint_acc[env_ids, joint_ids] = 0.0
508500
# Need to invalidate the buffer to trigger the update with the new root pose.
509501
self._data._body_state_w.timestamp = -1.0
510-
self._data._body_link_state_w.timestamp = -1.0
511-
self._data._body_com_state_w.timestamp = -1.0
502+
# self._data._body_link_state_w.timestamp = -1.0
503+
# self._data._body_com_state_w.timestamp = -1.0
512504
# set into simulation
513505
self.root_physx_view.set_dof_positions(self._data.joint_pos, indices=physx_env_ids)
514506
self.root_physx_view.set_dof_velocities(self._data.joint_vel, indices=physx_env_ids)

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

-20
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
import torch
77
import weakref
88

9-
import omni.log
109
import omni.physics.tensors.impl.api as physx
1110

1211
import omni.isaac.lab.utils.math as math_utils
@@ -75,11 +74,6 @@ def __init__(self, root_physx_view: physx.ArticulationView, device: str):
7574
self._joint_acc = TimestampedBuffer()
7675
self._joint_vel = TimestampedBuffer()
7776

78-
# deprecation warning check
79-
self._root_state_dep_warn = False
80-
self._body_state_dep_warn = False
81-
self._ignore_dep_warn = False
82-
8377
def update(self, dt: float):
8478
# update the simulation timestamp
8579
self._sim_timestamp += dt
@@ -274,13 +268,6 @@ def root_state_w(self):
274268
the linear and angular velocities are of the articulation root's center of mass frame.
275269
"""
276270

277-
if not self._root_state_dep_warn and not self._ignore_dep_warn:
278-
omni.log.warn(
279-
"DeprecationWarning: root_state_w and it's derived properties will be deprecated in a future release."
280-
" Please use root_link_state_w or root_com_state_w."
281-
)
282-
self._root_state_dep_warn = True
283-
284271
if self._root_state_w.timestamp < self._sim_timestamp:
285272
# read data from simulation
286273
pose = self._root_physx_view.get_root_transforms().clone()
@@ -347,13 +334,6 @@ def body_state_w(self):
347334
velocities are of the articulation links's center of mass frame.
348335
"""
349336

350-
if not self._body_state_dep_warn and not self._ignore_dep_warn:
351-
omni.log.warn(
352-
"DeprecationWarning: body_state_w and it's derived properties will be deprecated in a future release."
353-
" Please use body_link_state_w or body_com_state_w."
354-
)
355-
self._body_state_dep_warn = True
356-
357337
if self._body_state_w.timestamp < self._sim_timestamp:
358338
self._physics_sim_view.update_articulations_kinematic()
359339
# read data from simulation

0 commit comments

Comments
 (0)