Unverified Commit c6af307a authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fix the double ellipsis issue when resolving indices (#196)

# Description

Earlier in the code, we were using the `Ellipsis` object to index the
dimensions of the tensor. This led to situations where
we indexed multi-dimension tensors as: `x[..., ..., 0]`. This now leads
to errors with Python 3.10.

The MR replaces `Ellipsis` with the `slice(None)` object, which results
in indexing as: `x[:, :, 0]`.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] 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

---------
Co-authored-by: 's avatarFarbod Farshidian <ffarshidian@theaiinstitute.com>
parent 0396cf07
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.9.12" version = "0.9.13"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.9.13 (2023-10-20)
~~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Fixed the issue with double :obj:`Ellipsis` when indexing tensors with multiple dimensions.
The fix now uses :obj:`slice(None)` instead of :obj:`Ellipsis` to index the tensors.
0.9.12 (2023-10-18) 0.9.12 (2023-10-18)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -45,15 +45,15 @@ class ActuatorBase(ABC): ...@@ -45,15 +45,15 @@ class ActuatorBase(ABC):
"""The damping (D gain) of the PD controller. Shape is ``(num_envs, num_joints)``.""" """The damping (D gain) of the PD controller. Shape is ``(num_envs, num_joints)``."""
def __init__( def __init__(
self, cfg: ActuatorBaseCfg, joint_names: list[str], joint_ids: list[int] | Ellipsis, num_envs: int, device: str self, cfg: ActuatorBaseCfg, joint_names: list[str], joint_ids: Sequence[int], num_envs: int, device: str
): ):
"""Initialize the actuator. """Initialize the actuator.
Args: Args:
cfg: The configuration of the actuator model. cfg: The configuration of the actuator model.
joint_names: The joint names in the articulation. joint_names: The joint names in the articulation.
joint_ids: The joint indices in the articulation. If :obj:`Ellipsis`, then all the joints in the joint_ids: The joint indices in the articulation. If :obj:`slice(None)`, then all
articulation are part of the group. the joints in the articulation are part of the group.
num_envs: Number of articulations in the view. num_envs: Number of articulations in the view.
device: Device used for processing. device: Device used for processing.
""" """
...@@ -99,7 +99,7 @@ class ActuatorBase(ABC): ...@@ -99,7 +99,7 @@ class ActuatorBase(ABC):
"""Returns: A string representation of the actuator group.""" """Returns: A string representation of the actuator group."""
# resolve joint indices for printing # resolve joint indices for printing
joint_indices = self.joint_indices joint_indices = self.joint_indices
if joint_indices is Ellipsis: if joint_indices == slice(None):
joint_indices = list(range(self.num_joints)) joint_indices = list(range(self.num_joints))
return ( return (
f"<class {self.__class__.__name__}> object:\n" f"<class {self.__class__.__name__}> object:\n"
...@@ -124,11 +124,12 @@ class ActuatorBase(ABC): ...@@ -124,11 +124,12 @@ class ActuatorBase(ABC):
return self._joint_names return self._joint_names
@property @property
def joint_indices(self) -> list[int] | Ellipsis: def joint_indices(self) -> Sequence[int]:
"""Articulation's joint indices that are part of the group. """Articulation's joint indices that are part of the group.
Note: Note:
If :obj:`Ellipsis` is returned, then the group contains all the joints in the articulation. If :obj:`slice(None)` is returned, then the group contains all the joints in the articulation.
We do this to avoid unnecessary indexing of the joints for performance reasons.
""" """
return self._joint_indices return self._joint_indices
......
...@@ -101,7 +101,7 @@ class Articulation(RigidObject): ...@@ -101,7 +101,7 @@ class Articulation(RigidObject):
super().reset(env_ids) super().reset(env_ids)
# use ellipses object to skip initial indices. # use ellipses object to skip initial indices.
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# reset actuators # reset actuators
for actuator in self.actuators.values(): for actuator in self.actuators.values():
actuator.reset(env_ids) actuator.reset(env_ids)
...@@ -162,7 +162,7 @@ class Articulation(RigidObject): ...@@ -162,7 +162,7 @@ class Articulation(RigidObject):
def write_root_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None): def write_root_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None):
# resolve all indices # resolve all indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# note: we need to do this here since tensors are not set into simulation until step. # note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers # set into internal buffers
self._data.root_state_w[env_ids, :7] = root_pose.clone() self._data.root_state_w[env_ids, :7] = root_pose.clone()
...@@ -175,7 +175,7 @@ class Articulation(RigidObject): ...@@ -175,7 +175,7 @@ class Articulation(RigidObject):
def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None): def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
# resolve all indices # resolve all indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# note: we need to do this here since tensors are not set into simulation until step. # note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers # set into internal buffers
self._data.root_state_w[env_ids, 7:] = root_velocity.clone() self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
...@@ -199,9 +199,9 @@ class Articulation(RigidObject): ...@@ -199,9 +199,9 @@ class Articulation(RigidObject):
""" """
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set into internal buffers # set into internal buffers
self._data.joint_pos[env_ids, joint_ids] = position self._data.joint_pos[env_ids, joint_ids] = position
self._data.joint_vel[env_ids, joint_ids] = velocity self._data.joint_vel[env_ids, joint_ids] = velocity
...@@ -227,9 +227,9 @@ class Articulation(RigidObject): ...@@ -227,9 +227,9 @@ class Articulation(RigidObject):
# note: This function isn't setting the values for actuator models. (#128) # note: This function isn't setting the values for actuator models. (#128)
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set into internal buffers # set into internal buffers
self._data.joint_stiffness[env_ids, joint_ids] = stiffness self._data.joint_stiffness[env_ids, joint_ids] = stiffness
# set into simulation # set into simulation
...@@ -251,9 +251,9 @@ class Articulation(RigidObject): ...@@ -251,9 +251,9 @@ class Articulation(RigidObject):
# note: This function isn't setting the values for actuator models. (#128) # note: This function isn't setting the values for actuator models. (#128)
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set into internal buffers # set into internal buffers
self._data.joint_damping[env_ids, joint_ids] = damping self._data.joint_damping[env_ids, joint_ids] = damping
# set into simulation # set into simulation
...@@ -276,9 +276,9 @@ class Articulation(RigidObject): ...@@ -276,9 +276,9 @@ class Articulation(RigidObject):
# note: This function isn't setting the values for actuator models. (#128) # note: This function isn't setting the values for actuator models. (#128)
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set into internal buffers # set into internal buffers
torque_limit_all = self.root_physx_view.get_dof_max_forces() torque_limit_all = self.root_physx_view.get_dof_max_forces()
torque_limit_all[env_ids, joint_ids] = limits torque_limit_all[env_ids, joint_ids] = limits
...@@ -306,9 +306,9 @@ class Articulation(RigidObject): ...@@ -306,9 +306,9 @@ class Articulation(RigidObject):
""" """
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set targets # set targets
self._data.joint_pos_target[env_ids, joint_ids] = target self._data.joint_pos_target[env_ids, joint_ids] = target
...@@ -328,9 +328,9 @@ class Articulation(RigidObject): ...@@ -328,9 +328,9 @@ class Articulation(RigidObject):
""" """
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set targets # set targets
self._data.joint_vel_target[env_ids, joint_ids] = target self._data.joint_vel_target[env_ids, joint_ids] = target
...@@ -350,9 +350,9 @@ class Articulation(RigidObject): ...@@ -350,9 +350,9 @@ class Articulation(RigidObject):
""" """
# resolve indices # resolve indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
if joint_ids is None: if joint_ids is None:
joint_ids = ... joint_ids = slice(None)
# set targets # set targets
self._data.joint_effort_target[env_ids, joint_ids] = target self._data.joint_effort_target[env_ids, joint_ids] = target
...@@ -513,7 +513,7 @@ class Articulation(RigidObject): ...@@ -513,7 +513,7 @@ class Articulation(RigidObject):
) )
# for efficiency avoid indexing when over all indices # for efficiency avoid indexing when over all indices
if len(joint_names) == self.num_joints: if len(joint_names) == self.num_joints:
joint_ids = ... joint_ids = slice(None)
# create actuator collection # create actuator collection
actuator: ActuatorBase = actuator_cfg.class_type( actuator: ActuatorBase = actuator_cfg.class_type(
cfg=actuator_cfg, cfg=actuator_cfg,
......
...@@ -100,7 +100,7 @@ class RigidObject(AssetBase): ...@@ -100,7 +100,7 @@ class RigidObject(AssetBase):
def reset(self, env_ids: Sequence[int] | None = None): def reset(self, env_ids: Sequence[int] | None = None):
# resolve all indices # resolve all indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# reset external wrench # reset external wrench
self._external_force_b[env_ids] = 0.0 self._external_force_b[env_ids] = 0.0
self._external_torque_b[env_ids] = 0.0 self._external_torque_b[env_ids] = 0.0
...@@ -171,7 +171,7 @@ class RigidObject(AssetBase): ...@@ -171,7 +171,7 @@ class RigidObject(AssetBase):
""" """
# resolve all indices # resolve all indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# note: we need to do this here since tensors are not set into simulation until step. # note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers # set into internal buffers
self._data.root_state_w[env_ids, :7] = root_pose.clone() self._data.root_state_w[env_ids, :7] = root_pose.clone()
...@@ -190,7 +190,7 @@ class RigidObject(AssetBase): ...@@ -190,7 +190,7 @@ class RigidObject(AssetBase):
""" """
# resolve all indices # resolve all indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# note: we need to do this here since tensors are not set into simulation until step. # note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers # set into internal buffers
self._data.root_state_w[env_ids, 7:] = root_velocity.clone() self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
......
...@@ -122,7 +122,7 @@ class CommandGeneratorBase(ABC): ...@@ -122,7 +122,7 @@ class CommandGeneratorBase(ABC):
""" """
# resolve the environment IDs # resolve the environment IDs
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# set the command counter to zero # set the command counter to zero
self.command_counter[env_ids] = 0 self.command_counter[env_ids] = 0
# resample the command # resample the command
......
...@@ -65,7 +65,7 @@ class JointAction(ActionTerm): ...@@ -65,7 +65,7 @@ class JointAction(ActionTerm):
# Avoid indexing across all joints for efficiency # Avoid indexing across all joints for efficiency
if self._num_joints == self._asset.num_joints: if self._num_joints == self._asset.num_joints:
self._joint_ids = ... self._joint_ids = slice(None)
# create tensors for raw and processed actions # create tensors for raw and processed actions
self._raw_actions = torch.zeros(self.num_envs, self.action_dim, device=self.device) self._raw_actions = torch.zeros(self.num_envs, self.action_dim, device=self.device)
......
...@@ -76,7 +76,7 @@ class DifferentialInverseKinematicsAction(ActionTerm): ...@@ -76,7 +76,7 @@ class DifferentialInverseKinematicsAction(ActionTerm):
) )
# Avoid indexing across all joints for efficiency # Avoid indexing across all joints for efficiency
if self._num_joints == self._asset.num_joints: if self._num_joints == self._asset.num_joints:
self._joint_ids = ... self._joint_ids = slice(None)
# create the differential IK controller # create the differential IK controller
self._controller = DifferentialIKController(cfg=self.cfg.controller, num_envs=self.num_envs, device=self.device) self._controller = DifferentialIKController(cfg=self.cfg.controller, num_envs=self.num_envs, device=self.device)
......
...@@ -197,7 +197,7 @@ class ActionManager(ManagerBase): ...@@ -197,7 +197,7 @@ class ActionManager(ManagerBase):
""" """
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# reset the action history # reset the action history
self._prev_action[env_ids] = 0.0 self._prev_action[env_ids] = 0.0
self._action[env_ids] = 0.0 self._action[env_ids] = 0.0
......
...@@ -120,7 +120,7 @@ class CurriculumManager(ManagerBase): ...@@ -120,7 +120,7 @@ class CurriculumManager(ManagerBase):
""" """
# resolve environment indices # resolve environment indices
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# iterate over all the curriculum terms # iterate over all the curriculum terms
for name, term_cfg in zip(self._term_names, self._term_cfgs): for name, term_cfg in zip(self._term_names, self._term_cfgs):
state = term_cfg.func(self._env, env_ids, **term_cfg.params) state = term_cfg.func(self._env, env_ids, **term_cfg.params)
......
...@@ -99,7 +99,7 @@ class RewardManager(ManagerBase): ...@@ -99,7 +99,7 @@ class RewardManager(ManagerBase):
""" """
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# store information # store information
extras = {} extras = {}
for key in self._episode_sums.keys(): for key in self._episode_sums.keys():
......
...@@ -103,7 +103,7 @@ class TerminationManager(ManagerBase): ...@@ -103,7 +103,7 @@ class TerminationManager(ManagerBase):
""" """
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# add to episode dict # add to episode dict
extras = {} extras = {}
for key in self._episode_dones.keys(): for key in self._episode_dones.keys():
......
...@@ -135,7 +135,7 @@ class ContactSensor(SensorBase): ...@@ -135,7 +135,7 @@ class ContactSensor(SensorBase):
super().reset(env_ids) super().reset(env_ids)
# resolve None # resolve None
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# reset accumulative data buffers # reset accumulative data buffers
self._data.current_air_time[env_ids] = 0.0 self._data.current_air_time[env_ids] = 0.0
self._data.last_air_time[env_ids] = 0.0 self._data.last_air_time[env_ids] = 0.0
...@@ -223,7 +223,7 @@ class ContactSensor(SensorBase): ...@@ -223,7 +223,7 @@ class ContactSensor(SensorBase):
"""Fills the buffers of the sensor data.""" """Fills the buffers of the sensor data."""
# default to all sensors # default to all sensors
if len(env_ids) == self._num_envs: if len(env_ids) == self._num_envs:
env_ids = ... env_ids = slice(None)
# obtain the poses of the sensors: # obtain the poses of the sensors:
# TODO decide if we really to track poses -- This is the body's CoM. Not contact location. # TODO decide if we really to track poses -- This is the body's CoM. Not contact location.
pose = self.body_physx_view.get_transforms() pose = self.body_physx_view.get_transforms()
...@@ -257,7 +257,7 @@ class ContactSensor(SensorBase): ...@@ -257,7 +257,7 @@ class ContactSensor(SensorBase):
# since this function is called every frame, we can use the difference to get the elapsed time # since this function is called every frame, we can use the difference to get the elapsed time
elapsed_time = self._timestamp[env_ids] - self._timestamp_last_update[env_ids] elapsed_time = self._timestamp[env_ids] - self._timestamp_last_update[env_ids]
# -- check contact state of bodies # -- check contact state of bodies
is_contact = torch.norm(self._data.net_forces_w[env_ids, 0, :, :], dim=-1) > 1.0 is_contact = torch.norm(self._data.net_forces_w[env_ids, :, :], dim=-1) > 1.0
is_first_contact = (self._data.current_air_time[env_ids] > 0) * is_contact is_first_contact = (self._data.current_air_time[env_ids] > 0) * is_contact
# -- update ongoing timer for bodies air # -- update ongoing timer for bodies air
self._data.current_air_time[env_ids] += elapsed_time.unsqueeze(-1) self._data.current_air_time[env_ids] += elapsed_time.unsqueeze(-1)
......
...@@ -140,7 +140,7 @@ class SensorBase(ABC): ...@@ -140,7 +140,7 @@ class SensorBase(ABC):
""" """
# Resolve sensor ids # Resolve sensor ids
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
# Reset the timestamp for the sensors # Reset the timestamp for the sensors
self._timestamp[env_ids] = 0.0 self._timestamp[env_ids] = 0.0
self._timestamp_last_update[env_ids] = 0.0 self._timestamp_last_update[env_ids] = 0.0
......
...@@ -380,6 +380,9 @@ class SimulationContext(_SimulationContext): ...@@ -380,6 +380,9 @@ class SimulationContext(_SimulationContext):
self._render_throttle_counter = 0 self._render_throttle_counter = 0
# here we don't render viewport so don't need to flush flatcache # here we don't render viewport so don't need to flush flatcache
super().render() super().render()
elif self.render_mode == self.RenderMode.HEADLESS:
# we never want to render anything here -- camera rendering will also not work then?
pass
else: else:
# this is called even if we are in headless mode - we allow this for off-screen rendering # this is called even if we are in headless mode - we allow this for off-screen rendering
# manually flush the flatcache data to update Hydra textures # manually flush the flatcache data to update Hydra textures
......
...@@ -9,8 +9,8 @@ from typing import TYPE_CHECKING ...@@ -9,8 +9,8 @@ from typing import TYPE_CHECKING
import carb import carb
import omni.isaac.core.utils.prims as prim_utils import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.version import get_version
import omni.kit.commands import omni.kit.commands
from omni.isaac.version import get_version
from pxr import Gf, Sdf, Usd from pxr import Gf, Sdf, Usd
from omni.isaac.orbit.sim import loaders, schemas from omni.isaac.orbit.sim import loaders, schemas
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import torch
import unittest
class TestTorchOperations(unittest.TestCase):
"""Tests for assuring torch related operations used in Orbit."""
def test_array_slicing(self):
"""Check that using ellipsis and slices work for torch tensors."""
size = (400, 300, 5)
my_tensor = torch.rand(size, device="cuda:0")
self.assertEqual(my_tensor[..., 0].shape, (400, 300))
self.assertEqual(my_tensor[:, :, 0].shape, (400, 300))
self.assertEqual(my_tensor[slice(None), slice(None), 0].shape, (400, 300))
with self.assertRaises(IndexError):
my_tensor[..., ..., 0]
self.assertEqual(my_tensor[0, ...].shape, (300, 5))
self.assertEqual(my_tensor[0, :, :].shape, (300, 5))
self.assertEqual(my_tensor[0, slice(None), slice(None)].shape, (300, 5))
self.assertEqual(my_tensor[0, ..., ...].shape, (300, 5))
self.assertEqual(my_tensor[..., 0, 0].shape, (400,))
self.assertEqual(my_tensor[slice(None), 0, 0].shape, (400,))
self.assertEqual(my_tensor[:, 0, 0].shape, (400,))
if __name__ == "__main__":
unittest.main()
...@@ -201,7 +201,7 @@ class PickAndLiftSm: ...@@ -201,7 +201,7 @@ class PickAndLiftSm:
def reset_idx(self, env_ids: Sequence[int] = None): def reset_idx(self, env_ids: Sequence[int] = None):
"""Reset the state machine.""" """Reset the state machine."""
if env_ids is None: if env_ids is None:
env_ids = ... env_ids = slice(None)
self.sm_state[env_ids] = 0 self.sm_state[env_ids] = 0
self.sm_wait_time[env_ids] = 0.0 self.sm_wait_time[env_ids] = 0.0
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment