Skip to content

Commit

Permalink
Removes deprecation for root_state_w properties and setters (#1695)
Browse files Browse the repository at this point in the history
…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 <166445701+jtigue-bdai@users.noreply.github.com>
Co-authored-by: Kelly Guo <kellyg@nvidia.com>
Co-authored-by: Kelly Guo <kellyguo123@hotmail.com>
  • Loading branch information
3 people authored Jan 21, 2025
1 parent 7ed94ce commit 999c1e9
Show file tree
Hide file tree
Showing 88 changed files with 533 additions and 579 deletions.
4 changes: 2 additions & 2 deletions docs/source/migration/migrating_from_isaacgymenvs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -814,9 +814,9 @@ The ``progress_buf`` variable has also been renamed to ``episode_length_buf``.
| | |
| | self.joint_pos[env_ids] = joint_pos |
| | |
| | self.cartpole.write_root_link_pose_to_sim( |
| | self.cartpole.write_root_pose_to_sim( |
| | default_root_state[:, :7], env_ids) |
| | self.cartpole.write_root_com_velocity_to_sim( |
| | self.cartpole.write_root_velocity_to_sim( |
| | default_root_state[:, 7:], env_ids) |
| | self.cartpole.write_joint_state_to_sim( |
| | joint_pos, joint_vel, None, env_ids) |
Expand Down
8 changes: 4 additions & 4 deletions docs/source/migration/migrating_from_omniisaacgymenvs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -364,8 +364,8 @@ In Isaac Lab, ``root_pose`` and ``root_velocity`` have been combined into single

.. code-block::python
self.cartpole.write_root_link_pose_to_sim(default_root_state[:, :7], env_ids)
self.cartpole.write_root_com_velocity_to_sim(default_root_state[:, 7:], env_ids)
self.cartpole.write_root_pose_to_sim(default_root_state[:, :7], env_ids)
self.cartpole.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids)
Creating a New Environment
Expand Down Expand Up @@ -738,9 +738,9 @@ reset the ``episode_length_buf`` buffer.
| 1.0 - 2.0 * torch.rand(num_resets, device=self._device)) | self.joint_pos[env_ids] = joint_pos |
| | self.joint_vel[env_ids] = joint_vel |
| # apply resets | |
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_link_pose_to_sim( |
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_pose_to_sim( |
| self._cartpoles.set_joint_positions(dof_pos, indices=indices) | default_root_state[:, :7], env_ids) |
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_com_velocity_to_sim( |
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_velocity_to_sim( |
| | default_root_state[:, 7:], env_ids) |
| # bookkeeping | self.cartpole.write_joint_state_to_sim( |
| self.reset_buf[env_ids] = 0 | joint_pos, joint_vel, None, env_ids) |
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/01_assets/run_articulation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ Similar to a rigid object, an articulation also has a root state. This state cor
articulation tree. On top of the root state, an articulation also has joint states. These states correspond to the
joint positions and velocities.

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`
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`
methods. Similarly, we set the joint states by calling the :meth:`Articulation.write_joint_state_to_sim` method.
Finally, we call the :meth:`Articulation.reset` method to reset any internal buffers and caches.

Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/01_assets/run_deformable_object.rst
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ the average position of all the nodes in the mesh.
.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_deformable_object.py
:language: python
:start-at: # update buffers
:end-at: print(f"Root position (in world): {cube_object.data.root_link_pos_w[:, :3]}")
:end-at: print(f"Root position (in world): {cube_object.data.root_pos_w[:, :3]}")


The Code Execution
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/01_assets/run_rigid_object.rst
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ desired state of the rigid object prim into the world frame before setting it.
We use the :attr:`assets.RigidObject.data.default_root_state` attribute to get the default root state of the
spawned rigid object prims. This default state can be configured from the :attr:`assets.RigidObjectCfg.init_state`
attribute, which we left as identity in this tutorial. We then randomize the translation of the root state and
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.
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.
As the name suggests, this method writes the root state of the rigid object prim into the simulation buffer.

.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_rigid_object.py
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/05_controllers/run_diff_ik.rst
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ joint positions, current end-effector pose, and the Jacobian matrix.

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

Expand Down
2 changes: 1 addition & 1 deletion source/extensions/omni.isaac.lab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.30.5"
version = "0.30.6"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
29 changes: 29 additions & 0 deletions source/extensions/omni.isaac.lab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,35 @@
Changelog
---------

0.30.6 (2025-01-17)
~~~~~~~~~~~~~~~~~~~

Fixed
^^^^^

* removed deprecation of :attr:`omni.isaac.lab.assets.ArticulationData.root_state_w` and
:attr:`omni.isaac.lab.assets.ArticulationData.body_state_w` derived properties.
* removed deprecation of :meth:`omni.isaac.lab.assets.Articulation.write_root_state_to_sim`.
* replaced calls to :attr:`omni.isaac.lab.assets.ArticulationData.root_com_state_w` and
:attr:`omni.isaac.lab.assets.ArticulationData.root_link_state_w` with corresponding calls to
:attr:`omni.isaac.lab.assets.ArticulationData.root_state_w`.
* replaced calls to :attr:`omni.isaac.lab.assets.ArticulationData.body_com_state_w` and
:attr:`omni.isaac.lab.assets.ArticulationData.body_link_state_w` properties with corresponding calls to
:attr:`omni.isaac.lab.assets.ArticulationData.body_state_w` properties.
* removed deprecation of :attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` derived properties .
* removed deprecation of :meth:`omni.isaac.lab.assets.RigidObject.write_root_state_to_sim`.
* replaced calls to :attr:`omni.isaac.lab.assets.RigidObjectData.root_com_state_w` and
:attr:`omni.isaac.lab.assets.RigidObjectData.root_link_state_w` properties with corresponding calls to
:attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` properties.
* removed deprecation of :attr:`omni.isaac.lab.assets.RigidObjectCollectionData.root_state_w` derived properties.
* removed deprecation of :meth:`omni.isaac.lab.assets.RigidObjectCollection.write_root_state_to_sim`.
* replaced calls to :attr:`omni.isaac.lab.assets.RigidObjectCollectionData.root_com_state_w` and
:attr:`omni.isaac.lab.assets.RigidObjectData.root_link_state_w` properties with corresponding calls to
:attr:`omni.isaac.lab.assets.RigidObjectData.root_state_w` properties.
* fixed indexing issue in ``write_root_link_velocity_to_sim`` in :class:`omni.isaac.lab.assets.RigidObject`
* fixed index broadcasting in ``write_object_link_velocity_to_sim`` and ``write_object_com_pose_to_sim`` in :class:`omni.isaac.lab.assets.RigidObjectCollection`


0.30.5 (2025-01-14)
~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,10 +98,6 @@ def __init__(self, cfg: ArticulationCfg):
"""
super().__init__(cfg)

self._root_state_dep_warn = False
self._root_pose_dep_warn = False
self._root_vel_dep_warn = False

"""
Properties
"""
Expand Down Expand Up @@ -285,14 +281,6 @@ def write_root_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[in
env_ids: Environment indices. If None, then all indices are used.
"""

# deprecation warning
if not self._root_state_dep_warn:
omni.log.warn(
"DeprecationWarning: Articluation.write_root_state_to_sim will be removed in a future release. Please"
" use write_root_link_state_to_sim or write_root_com_state_to_sim instead."
)
self._root_state_dep_warn = True

# set into simulation
self.write_root_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
Expand Down Expand Up @@ -334,15 +322,21 @@ def write_root_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int]
root_pose: Root poses in simulation frame. Shape is (len(env_ids), 7).
env_ids: Environment indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_pose_dep_warn:
omni.log.warn(
"DeprecationWarning: Articluation.write_root_pos_to_sim will be removed in a future release. Please use"
" write_root_link_pose_to_sim or write_root_com_pose_to_sim instead."
)
self._root_pose_dep_warn = True

self.write_root_link_pose_to_sim(root_pose, env_ids)
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, :7] = root_pose.clone()
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_state_w[:, :7].clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
# Need to invalidate the buffer to trigger the update with the new root pose.
self._data._body_state_w.timestamp = -1.0
# set into simulation
self.root_physx_view.set_root_transforms(root_poses_xyzw, indices=physx_env_ids)

def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root link pose over selected environment indices into the simulation.
Expand All @@ -361,9 +355,7 @@ def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_link_state_w[env_ids, :7] = root_pose.clone()
self._data._ignore_dep_warn = True
self._data.root_state_w[env_ids, :7] = self._data.root_link_state_w[env_ids, :7]
self._data._ignore_dep_warn = False
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_link_state_w[:, :7].clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
Expand Down Expand Up @@ -413,15 +405,17 @@ def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Seque
root_velocity: Root center of mass velocities in simulation world frame. Shape is (len(env_ids), 6).
env_ids: Environment indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_vel_dep_warn:
omni.log.warn(
"DeprecationWarning: Articluation.write_root_velocity_to_sim will be removed in a future release."
" Please use write_root_link_velocity_to_sim or write_root_com_velocity_to_sim instead."
)
self._root_vel_dep_warn = True

self.write_root_com_velocity_to_sim(root_velocity=root_velocity, env_ids=env_ids)
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
self._data.body_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_root_velocities(self._data.root_state_w[:, 7:], indices=physx_env_ids)

def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass velocity over selected environment indices into the simulation.
Expand All @@ -442,9 +436,7 @@ def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: S
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_com_state_w[env_ids, 7:] = root_velocity.clone()
self._data._ignore_dep_warn = True
self._data.root_state_w[env_ids, 7:] = self._data.root_com_state_w[env_ids, 7:]
self._data._ignore_dep_warn = False
self._data.body_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_root_velocities(self._data.root_com_state_w[:, 7:], indices=physx_env_ids)
Expand Down Expand Up @@ -507,8 +499,8 @@ def write_joint_state_to_sim(
self._data.joint_acc[env_ids, joint_ids] = 0.0
# Need to invalidate the buffer to trigger the update with the new root pose.
self._data._body_state_w.timestamp = -1.0
self._data._body_link_state_w.timestamp = -1.0
self._data._body_com_state_w.timestamp = -1.0
# self._data._body_link_state_w.timestamp = -1.0
# self._data._body_com_state_w.timestamp = -1.0
# set into simulation
self.root_physx_view.set_dof_positions(self._data.joint_pos, indices=physx_env_ids)
self.root_physx_view.set_dof_velocities(self._data.joint_vel, indices=physx_env_ids)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import torch
import weakref

import omni.log
import omni.physics.tensors.impl.api as physx

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

# deprecation warning check
self._root_state_dep_warn = False
self._body_state_dep_warn = False
self._ignore_dep_warn = False

def update(self, dt: float):
# update the simulation timestamp
self._sim_timestamp += dt
Expand Down Expand Up @@ -274,13 +268,6 @@ def root_state_w(self):
the linear and angular velocities are of the articulation root's center of mass frame.
"""

if not self._root_state_dep_warn and not self._ignore_dep_warn:
omni.log.warn(
"DeprecationWarning: root_state_w and it's derived properties will be deprecated in a future release."
" Please use root_link_state_w or root_com_state_w."
)
self._root_state_dep_warn = True

if self._root_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_root_transforms().clone()
Expand Down Expand Up @@ -347,13 +334,6 @@ def body_state_w(self):
velocities are of the articulation links's center of mass frame.
"""

if not self._body_state_dep_warn and not self._ignore_dep_warn:
omni.log.warn(
"DeprecationWarning: body_state_w and it's derived properties will be deprecated in a future release."
" Please use body_link_state_w or body_com_state_w."
)
self._body_state_dep_warn = True

if self._body_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
Expand Down
Loading

0 comments on commit 999c1e9

Please sign in to comment.