Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Removes deprecation for root_state_w properties and setters #1695

Merged
merged 9 commits into from
Jan 21, 2025
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
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.4"
version = "0.30.5"

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

0.30.5 (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.


0.30.4 (2025-01-08)
~~~~~~~~~~~~~~~~~~~

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,13 +322,6 @@ 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)

Expand Down Expand Up @@ -413,13 +394,6 @@ 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)

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
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,6 @@ def __init__(self, cfg: RigidObjectCfg):
cfg: A configuration instance.
"""
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 @@ -159,13 +156,6 @@ def write_root_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[in
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_state_dep_warn:
omni.log.warn(
"DeprecationWarning: RigidObject.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)
Expand Down Expand Up @@ -208,13 +198,6 @@ 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: RigidObject.write_root_pose_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)

Expand Down Expand Up @@ -282,13 +265,6 @@ 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: RigidObject.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)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,6 @@ def __init__(self, root_physx_view: physx.RigidBodyView, device: str):
self._root_com_state_w = TimestampedBuffer()
self._body_acc_w = TimestampedBuffer()

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

def update(self, dt: float):
"""Updates the data for the rigid object.

Expand Down Expand Up @@ -121,12 +117,6 @@ def root_state_w(self):
The position and orientation are of the rigid body's actor frame. Meanwhile, the linear and angular
velocities are of the rigid body'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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,6 @@ def __init__(self, cfg: RigidObjectCollectionCfg):

self._debug_vis_handle = None

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

"""
Properties
"""
Expand Down Expand Up @@ -226,13 +222,6 @@ def write_object_state_to_sim(
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_state_dep_warn:
omni.log.warn(
"DeprecationWarning: RigidObjectCollection.write_object_state_to_sim will be removed in a future"
" release. Please use write_object_link_state_to_sim or write_object_com_state_to_sim instead."
)
self._root_state_dep_warn = True

# set into simulation
self.write_object_pose_to_sim(object_state[..., :7], env_ids=env_ids, object_ids=object_ids)
Expand Down Expand Up @@ -291,13 +280,6 @@ def write_object_pose_to_sim(
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_pose_dep_warn:
omni.log.warn(
"DeprecationWarning: RigidObjectCollection.write_object_pose_to_sim will be removed in a future"
" release. Please use write_object_link_pose_to_sim or write_object_com_pose_to_sim instead."
)
self._root_pose_dep_warn = True

self.write_object_link_pose_to_sim(object_pose, env_ids, object_ids)

Expand Down Expand Up @@ -388,13 +370,6 @@ def write_object_velocity_to_sim(
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# deprecation warning
if not self._root_vel_dep_warn:
omni.log.warn(
"DeprecationWarning: RigidObjectCollection.write_object_velocity_to_sim will be removed in a future"
" release. Please use write_object_link_velocity_to_sim or write_object_com_velocity_to_sim instead."
)
self._root_vel_dep_warn = True

self.write_object_com_velocity_to_sim(object_velocity=object_velocity, env_ids=env_ids, object_ids=object_ids)

Expand Down
Loading
Loading