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

Changes link names ordering in articulation to follow PhysX (#454)

# Description

This MR fixes an issue with the `Articulation` class. The indexing of
body names inside the articulation view is not the same as in the body
view. This affects any quantity of bodies (such as Jacobians) you try to
get directly from the articulation view.

The MR changes the `Articulation` class to follow the internal PhysX
articulation-view ordering of the link names. It deals internally with
re-ordering the articulation-link indices to body-view indices where
needed.

With this change, users no longer need to work with `body_physx_view` as
it will lead to unexpected behaviors. The MR removes this property from
the `RigidObject` and `Articulation` class.

Fixes #453

## 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`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have run all the tests with `./orbit.sh --test` and they pass
- [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
parent e682605e
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.13.1" version = "0.14.0"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.14.0 (2024-03-15)
~~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Fixed the ordering of body names used in the :class:`omni.isaac.orbit.assets.Articulation` class. Earlier,
the body names were not following the same ordering as the bodies in the articulation. This led
to issues when using the body names to access data related to the links from the articulation view
(such as Jacobians, mass matrices, etc.).
Removed
^^^^^^^
* Removed the attribute :attr:`body_physx_view` from the :class:`omni.isaac.orbit.assets.RigidObject`
and :class:`omni.isaac.orbit.assets.Articulation` classes. These were causing confusions when used
with articulation view since the body names were not following the same ordering.
0.13.1 (2024-03-14) 0.13.1 (2024-03-14)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -9,6 +9,7 @@ ...@@ -9,6 +9,7 @@
from __future__ import annotations from __future__ import annotations
import torch import torch
import warnings
from collections.abc import Sequence from collections.abc import Sequence
from prettytable import PrettyTable from prettytable import PrettyTable
from typing import TYPE_CHECKING from typing import TYPE_CHECKING
...@@ -50,8 +51,7 @@ class Articulation(RigidObject): ...@@ -50,8 +51,7 @@ class Articulation(RigidObject):
The articulation class is a subclass of the :class:`RigidObject` class. Therefore, it inherits The articulation class is a subclass of the :class:`RigidObject` class. Therefore, it inherits
all the functionality of the rigid object class. In case of an articulation, the :attr:`root_physx_view` all the functionality of the rigid object class. In case of an articulation, the :attr:`root_physx_view`
attribute corresponds to the articulation root view and can be used to access the articulation attribute corresponds to the articulation root view and can be used to access the articulation
related data. The :attr:`body_physx_view` attribute corresponds to the rigid body view of the articulated related data.
links and can be used to access the rigid body related data.
The articulation class also provides the functionality to augment the simulation of an articulated The articulation class also provides the functionality to augment the simulation of an articulated
system with custom actuator models. These models can either be explicit or implicit, as detailed in system with custom actuator models. These models can either be explicit or implicit, as detailed in
...@@ -115,24 +115,49 @@ class Articulation(RigidObject): ...@@ -115,24 +115,49 @@ class Articulation(RigidObject):
@property @property
def num_joints(self) -> int: def num_joints(self) -> int:
"""Number of joints in articulation.""" """Number of joints in articulation."""
return self.root_physx_view.max_dofs return self.root_physx_view.shared_metatype.dof_count
@property @property
def num_bodies(self) -> int: def num_bodies(self) -> int:
"""Number of bodies in articulation.""" """Number of bodies in articulation."""
return self.root_physx_view.max_links return self.root_physx_view.shared_metatype.link_count
@property @property
def joint_names(self) -> list[str]: def joint_names(self) -> list[str]:
"""Ordered names of joints in articulation.""" """Ordered names of joints in articulation."""
return self.root_physx_view.shared_metatype.dof_names return self.root_physx_view.shared_metatype.dof_names
@property
def body_names(self) -> list[str]:
"""Ordered names of bodies in articulation."""
return self.root_physx_view.shared_metatype.link_names
@property @property
def root_physx_view(self) -> physx.ArticulationView: def root_physx_view(self) -> physx.ArticulationView:
"""Articulation view for the asset (PhysX).
Note:
Use this view with caution. It requires handling of tensors in a specific way.
"""
return self._root_physx_view return self._root_physx_view
@property @property
def body_physx_view(self) -> physx.RigidBodyView: def body_physx_view(self) -> physx.RigidBodyView:
"""Rigid body view for the asset (PhysX).
.. deprecated:: v0.3.0
In previous versions, this attribute returned the rigid body view over all the links of the articulation.
However, this led to confusion with the link ordering as they were not ordered in the same way as the
articulation view.
Therefore, this attribute will be removed in v0.3.0. Please use the :attr:`root_physx_view` attribute
instead.
"""
dep_msg = "The attribute 'body_physx_view' will be removed in v0.3.0. Please use 'root_physx_view' instead."
warnings.warn(dep_msg, DeprecationWarning)
carb.log_error(dep_msg)
return self._body_physx_view return self._body_physx_view
""" """
...@@ -154,28 +179,46 @@ class Articulation(RigidObject): ...@@ -154,28 +179,46 @@ class Articulation(RigidObject):
If any explicit actuators are present, then the actuator models are used to compute the If any explicit actuators are present, then the actuator models are used to compute the
joint commands. Otherwise, the joint commands are directly set into the simulation. joint commands. Otherwise, the joint commands are directly set into the simulation.
""" """
super().write_data_to_sim() # write external wrench
# write commands if self.has_external_wrench:
# apply external forces and torques
self._body_physx_view.apply_forces_and_torques_at_position(
force_data=self._external_force_body_view_b.view(-1, 3),
torque_data=self._external_torque_body_view_b.view(-1, 3),
position_data=None,
indices=self._ALL_BODY_INDICES,
is_global=False,
)
# apply actuator models
self._apply_actuator_model() self._apply_actuator_model()
# apply actions into simulation # write actions into simulation
self.root_physx_view.set_dof_actuation_forces(self._joint_effort_target_sim, self._ALL_INDICES) self.root_physx_view.set_dof_actuation_forces(self._joint_effort_target_sim, self._ALL_INDICES)
# position and velocity targets only for implicit actuators # position and velocity targets only for implicit actuators
if self._has_implicit_actuators: if self._has_implicit_actuators:
self.root_physx_view.set_dof_position_targets(self._joint_pos_target_sim, self._ALL_INDICES) self.root_physx_view.set_dof_position_targets(self._joint_pos_target_sim, self._ALL_INDICES)
self.root_physx_view.set_dof_velocity_targets(self._joint_vel_target_sim, self._ALL_INDICES) self.root_physx_view.set_dof_velocity_targets(self._joint_vel_target_sim, self._ALL_INDICES)
def update(self, dt: float | None = None): def update(self, dt: float):
# -- root state (note: we roll the quaternion to match the convention used in Isaac Sim -- wxyz) # -- root state (note: we roll the quaternion to match the convention used in Isaac Sim -- wxyz)
self._data.root_state_w[:, :7] = self.root_physx_view.get_root_transforms() self._data.root_state_w[:, :7] = self.root_physx_view.get_root_transforms()
self._data.root_state_w[:, 3:7] = math_utils.convert_quat(self._data.root_state_w[:, 3:7], to="wxyz") self._data.root_state_w[:, 3:7] = math_utils.convert_quat(self._data.root_state_w[:, 3:7], to="wxyz")
self._data.root_state_w[:, 7:] = self.root_physx_view.get_root_velocities() self._data.root_state_w[:, 7:] = self.root_physx_view.get_root_velocities()
# -- body-state (note: we roll the quaternion to match the convention used in Isaac Sim -- wxyz)
self._data.body_state_w[..., :7] = self.root_physx_view.get_link_transforms()
self._data.body_state_w[..., 3:7] = math_utils.convert_quat(self._data.body_state_w[..., 3:7], to="wxyz")
self._data.body_state_w[..., 7:] = self.root_physx_view.get_link_velocities()
# -- joint states # -- joint states
self._data.joint_pos[:] = self.root_physx_view.get_dof_positions() self._data.joint_pos[:] = self.root_physx_view.get_dof_positions()
self._data.joint_vel[:] = self.root_physx_view.get_dof_velocities() self._data.joint_vel[:] = self.root_physx_view.get_dof_velocities()
self._data.joint_acc[:] = (self._data.joint_vel - self._previous_joint_vel) / dt self._data.joint_acc[:] = (self._data.joint_vel - self._previous_joint_vel) / dt
# -- update common data # -- update common data
# note: these are computed in the base class # note: these are computed in the base class
self._update_common_data(dt) self._update_common_data(dt)
# -- update history buffers # -- update history buffers
self._previous_joint_vel[:] = self._data.joint_vel[:] self._previous_joint_vel[:] = self._data.joint_vel[:]
...@@ -200,6 +243,24 @@ class Articulation(RigidObject): ...@@ -200,6 +243,24 @@ class Articulation(RigidObject):
# find joints # find joints
return string_utils.resolve_matching_names(name_keys, joint_subset) return string_utils.resolve_matching_names(name_keys, joint_subset)
"""
Operations - Setters.
"""
def set_external_force_and_torque(
self,
forces: torch.Tensor,
torques: torch.Tensor,
body_ids: Sequence[int] | slice | None = None,
env_ids: Sequence[int] | None = None,
):
# call parent to set the external forces and torques into buffers
super().set_external_force_and_torque(forces, torques, body_ids, env_ids)
# reordering of the external forces and torques to match the body view ordering
if self.has_external_wrench:
self._external_force_body_view_b = self._external_force_b[:, self._body_view_ordering]
self._external_torque_body_view_b = self._external_torque_b[:, self._body_view_ordering]
""" """
Operations - Writers. Operations - Writers.
""" """
...@@ -501,6 +562,17 @@ class Articulation(RigidObject): ...@@ -501,6 +562,17 @@ class Articulation(RigidObject):
body_names_regex = f"{self.cfg.prim_path}/{body_names_regex}" body_names_regex = f"{self.cfg.prim_path}/{body_names_regex}"
self._body_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex.replace(".*", "*")) self._body_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex.replace(".*", "*"))
# create ordering from articulation view to body view for body names
# note: we need to do this since the body view is not ordered in the same way as the articulation view
# -- root view
root_view_body_names = self.body_names
# -- body view
prim_paths = self._body_physx_view.prim_paths[: self.num_bodies]
body_view_body_names = [path.split("/")[-1] for path in prim_paths]
# -- mapping from articulation view to body view
self._body_view_ordering = [body_view_body_names.index(name) for name in root_view_body_names]
self._body_view_ordering = torch.tensor(self._body_view_ordering, dtype=torch.long, device=self.device)
# log information about the articulation # log information about the articulation
carb.log_info(f"Articulation initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.") carb.log_info(f"Articulation initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
carb.log_info(f"Is fixed root: {self.is_fixed_base}") carb.log_info(f"Is fixed root: {self.is_fixed_base}")
......
...@@ -25,30 +25,30 @@ class ArticulationData(RigidObjectData): ...@@ -25,30 +25,30 @@ class ArticulationData(RigidObjectData):
## ##
default_joint_pos: torch.Tensor = None default_joint_pos: torch.Tensor = None
"""Default joint positions of all joints. Shape is (count, num_joints).""" """Default joint positions of all joints. Shape is (num_instances, num_joints)."""
default_joint_vel: torch.Tensor = None default_joint_vel: torch.Tensor = None
"""Default joint velocities of all joints. Shape is (count, num_joints).""" """Default joint velocities of all joints. Shape is (num_instances, num_joints)."""
## ##
# Joint states <- From simulation. # Joint states <- From simulation.
## ##
joint_pos: torch.Tensor = None joint_pos: torch.Tensor = None
"""Joint positions of all joints. Shape is (count, num_joints).""" """Joint positions of all joints. Shape is (num_instances, num_joints)."""
joint_vel: torch.Tensor = None joint_vel: torch.Tensor = None
"""Joint velocities of all joints. Shape is (count, num_joints).""" """Joint velocities of all joints. Shape is (num_instances, num_joints)."""
joint_acc: torch.Tensor = None joint_acc: torch.Tensor = None
"""Joint acceleration of all joints. Shape is (count, num_joints).""" """Joint acceleration of all joints. Shape is (num_instances, num_joints)."""
## ##
# Joint commands -- Set into simulation. # Joint commands -- Set into simulation.
## ##
joint_pos_target: torch.Tensor = None joint_pos_target: torch.Tensor = None
"""Joint position targets commanded by the user. Shape is (count, num_joints). """Joint position targets commanded by the user. Shape is (num_instances, num_joints).
For an implicit actuator model, the targets are directly set into the simulation. For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`), For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
...@@ -56,7 +56,7 @@ class ArticulationData(RigidObjectData): ...@@ -56,7 +56,7 @@ class ArticulationData(RigidObjectData):
""" """
joint_vel_target: torch.Tensor = None joint_vel_target: torch.Tensor = None
"""Joint velocity targets commanded by the user. Shape is (count, num_joints). """Joint velocity targets commanded by the user. Shape is (num_instances, num_joints).
For an implicit actuator model, the targets are directly set into the simulation. For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`), For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
...@@ -64,7 +64,7 @@ class ArticulationData(RigidObjectData): ...@@ -64,7 +64,7 @@ class ArticulationData(RigidObjectData):
""" """
joint_effort_target: torch.Tensor = None joint_effort_target: torch.Tensor = None
"""Joint effort targets commanded by the user. Shape is (count, num_joints). """Joint effort targets commanded by the user. Shape is (num_instances, num_joints).
For an implicit actuator model, the targets are directly set into the simulation. For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`), For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
...@@ -72,23 +72,23 @@ class ArticulationData(RigidObjectData): ...@@ -72,23 +72,23 @@ class ArticulationData(RigidObjectData):
""" """
joint_stiffness: torch.Tensor = None joint_stiffness: torch.Tensor = None
"""Joint stiffness provided to simulation. Shape is (count, num_joints).""" """Joint stiffness provided to simulation. Shape is (num_instances, num_joints)."""
joint_damping: torch.Tensor = None joint_damping: torch.Tensor = None
"""Joint damping provided to simulation. Shape is (count, num_joints).""" """Joint damping provided to simulation. Shape is (num_instances, num_joints)."""
joint_armature: torch.Tensor = None joint_armature: torch.Tensor = None
"""Joint armature provided to simulation. Shape is (count, num_joints).""" """Joint armature provided to simulation. Shape is (num_instances, num_joints)."""
joint_friction: torch.Tensor = None joint_friction: torch.Tensor = None
"""Joint friction provided to simulation. Shape is (count, num_joints).""" """Joint friction provided to simulation. Shape is (num_instances, num_joints)."""
## ##
# Joint commands -- Explicit actuators. # Joint commands -- Explicit actuators.
## ##
computed_torque: torch.Tensor = None computed_torque: torch.Tensor = None
"""Joint torques computed from the actuator model (before clipping). Shape is (count, num_joints). """Joint torques computed from the actuator model (before clipping). Shape is (num_instances, num_joints).
This quantity is the raw torque output from the actuator mode, before any clipping is applied. This quantity is the raw torque output from the actuator mode, before any clipping is applied.
It is exposed for users who want to inspect the computations inside the actuator model. It is exposed for users who want to inspect the computations inside the actuator model.
...@@ -98,7 +98,7 @@ class ArticulationData(RigidObjectData): ...@@ -98,7 +98,7 @@ class ArticulationData(RigidObjectData):
""" """
applied_torque: torch.Tensor = None applied_torque: torch.Tensor = None
"""Joint torques applied from the actuator model (after clipping). Shape is (count, num_joints). """Joint torques applied from the actuator model (after clipping). Shape is (num_instances, num_joints).
These torques are set into the simulation, after clipping the :attr:`computed_torque` based on the These torques are set into the simulation, after clipping the :attr:`computed_torque` based on the
actuator model. actuator model.
...@@ -111,10 +111,10 @@ class ArticulationData(RigidObjectData): ...@@ -111,10 +111,10 @@ class ArticulationData(RigidObjectData):
## ##
soft_joint_pos_limits: torch.Tensor = None soft_joint_pos_limits: torch.Tensor = None
"""Joint positions limits for all joints. Shape is (count, num_joints, 2).""" """Joint positions limits for all joints. Shape is (num_instances, num_joints, 2)."""
soft_joint_vel_limits: torch.Tensor = None soft_joint_vel_limits: torch.Tensor = None
"""Joint velocity limits for all joints. Shape is (count, num_joints).""" """Joint velocity limits for all joints. Shape is (num_instances, num_joints)."""
gear_ratio: torch.Tensor = None gear_ratio: torch.Tensor = None
"""Gear ratio for relating motor torques to applied Joint torques. Shape is (count, num_joints).""" """Gear ratio for relating motor torques to applied Joint torques. Shape is (num_instances, num_joints)."""
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
from __future__ import annotations from __future__ import annotations
import torch import torch
import warnings
from collections.abc import Sequence from collections.abc import Sequence
from typing import TYPE_CHECKING from typing import TYPE_CHECKING
...@@ -33,10 +34,7 @@ class RigidObject(AssetBase): ...@@ -33,10 +34,7 @@ class RigidObject(AssetBase):
For an asset to be considered a rigid object, the root prim of the asset must have the `USD RigidBodyAPI`_ For an asset to be considered a rigid object, the root prim of the asset must have the `USD RigidBodyAPI`_
applied to it. This API is used to define the simulation properties of the rigid body. On playing the applied to it. This API is used to define the simulation properties of the rigid body. On playing the
simulation, the physics engine will automatically register the rigid body and create a corresponding simulation, the physics engine will automatically register the rigid body and create a corresponding
rigid body handle. This handle can be accessed using the :attr:`root_physx_view` and :attr:`body_physx_view` rigid body handle. This handle can be accessed using the :attr:`root_physx_view` attribute.
attributes. For a single rigid body asset, the :attr:`root_physx_view` and :attr:`body_physx_view` attributes
are the same. However, these are different for articulated assets as explained in the :class:`Articulation`
class.
.. note:: .. note::
...@@ -81,7 +79,7 @@ class RigidObject(AssetBase): ...@@ -81,7 +79,7 @@ class RigidObject(AssetBase):
@property @property
def body_names(self) -> list[str]: def body_names(self) -> list[str]:
"""Ordered names of bodies in articulation.""" """Ordered names of bodies in articulation."""
prim_paths = self.body_physx_view.prim_paths[: self.num_bodies] prim_paths = self.root_physx_view.prim_paths[: self.num_bodies]
return [path.split("/")[-1] for path in prim_paths] return [path.split("/")[-1] for path in prim_paths]
@property @property
...@@ -95,12 +93,17 @@ class RigidObject(AssetBase): ...@@ -95,12 +93,17 @@ class RigidObject(AssetBase):
@property @property
def body_physx_view(self) -> physx.RigidBodyView: def body_physx_view(self) -> physx.RigidBodyView:
"""View for the bodies in the asset (PhysX). """Rigid body view for the asset (PhysX).
.. deprecated:: v0.3.0
The attribute 'body_physx_view' will be removed in v0.3.0. Please use :attr:`root_physx_view` instead.
Note:
Use this view with caution. It requires handling of tensors in a specific way.
""" """
return self._body_physx_view dep_msg = "The attribute 'body_physx_view' will be removed in v0.3.0. Please use 'root_physx_view' instead."
warnings.warn(dep_msg, DeprecationWarning)
carb.log_error(dep_msg)
return self.root_physx_view
""" """
Operations. Operations.
...@@ -125,7 +128,7 @@ class RigidObject(AssetBase): ...@@ -125,7 +128,7 @@ class RigidObject(AssetBase):
""" """
# write external wrench # write external wrench
if self.has_external_wrench: if self.has_external_wrench:
self.body_physx_view.apply_forces_and_torques_at_position( self.root_physx_view.apply_forces_and_torques_at_position(
force_data=self._external_force_b.view(-1, 3), force_data=self._external_force_b.view(-1, 3),
torque_data=self._external_torque_b.view(-1, 3), torque_data=self._external_torque_b.view(-1, 3),
position_data=None, position_data=None,
...@@ -138,6 +141,10 @@ class RigidObject(AssetBase): ...@@ -138,6 +141,10 @@ class RigidObject(AssetBase):
self._data.root_state_w[:, :7] = self.root_physx_view.get_transforms() self._data.root_state_w[:, :7] = self.root_physx_view.get_transforms()
self._data.root_state_w[:, 3:7] = math_utils.convert_quat(self._data.root_state_w[:, 3:7], to="wxyz") self._data.root_state_w[:, 3:7] = math_utils.convert_quat(self._data.root_state_w[:, 3:7], to="wxyz")
self._data.root_state_w[:, 7:] = self.root_physx_view.get_velocities() self._data.root_state_w[:, 7:] = self.root_physx_view.get_velocities()
# -- body-state (note: for rigid objects, we only have one body so we just copy the root state)
self._data.body_state_w[:] = self._data.root_state_w.view(-1, self.num_bodies, 13)
# -- update common data # -- update common data
self._update_common_data(dt) self._update_common_data(dt)
...@@ -242,7 +249,8 @@ class RigidObject(AssetBase): ...@@ -242,7 +249,8 @@ class RigidObject(AssetBase):
.. note:: .. note::
This function does not apply the external wrench to the simulation. It only fills the buffers with This function does not apply the external wrench to the simulation. It only fills the buffers with
the desired values. To apply the external wrench, call the :meth:`write_data_to_sim` function. the desired values. To apply the external wrench, call the :meth:`write_data_to_sim` function
right before the simulation step.
Args: Args:
forces: External forces in bodies' local frame. Shape is (len(env_ids), len(body_ids), 3). forces: External forces in bodies' local frame. Shape is (len(env_ids), len(body_ids), 3).
...@@ -269,8 +277,7 @@ class RigidObject(AssetBase): ...@@ -269,8 +277,7 @@ class RigidObject(AssetBase):
# note: we need to do this complicated indexing since torch doesn't support multi-indexing # note: we need to do this complicated indexing since torch doesn't support multi-indexing
# create global body indices from env_ids and env_body_ids # create global body indices from env_ids and env_body_ids
# (env_id * total_bodies_per_env) + body_id # (env_id * total_bodies_per_env) + body_id
total_bodies_per_env = self.body_physx_view.count // self.root_physx_view.count indices = body_ids.repeat(len(env_ids), 1) + env_ids.unsqueeze(1) * self.num_bodies
indices = body_ids.repeat(len(env_ids), 1) + env_ids.unsqueeze(1) * total_bodies_per_env
indices = indices.view(-1) indices = indices.view(-1)
# set into internal buffers # set into internal buffers
# note: these are applied in the write_to_sim function # note: these are applied in the write_to_sim function
...@@ -306,7 +313,6 @@ class RigidObject(AssetBase): ...@@ -306,7 +313,6 @@ class RigidObject(AssetBase):
root_prim_path_expr = self.cfg.prim_path + root_prim_path[len(template_prim_path) :] root_prim_path_expr = self.cfg.prim_path + root_prim_path[len(template_prim_path) :]
# -- object view # -- object view
self._root_physx_view = self._physics_sim_view.create_rigid_body_view(root_prim_path_expr.replace(".*", "*")) self._root_physx_view = self._physics_sim_view.create_rigid_body_view(root_prim_path_expr.replace(".*", "*"))
self._body_physx_view = self._root_physx_view
# log information about the articulation # log information about the articulation
carb.log_info(f"Rigid body initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.") carb.log_info(f"Rigid body initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
carb.log_info(f"Number of instances: {self.num_instances}") carb.log_info(f"Number of instances: {self.num_instances}")
...@@ -321,7 +327,9 @@ class RigidObject(AssetBase): ...@@ -321,7 +327,9 @@ class RigidObject(AssetBase):
"""Create buffers for storing data.""" """Create buffers for storing data."""
# constants # constants
self._ALL_INDICES = torch.arange(self.num_instances, dtype=torch.long, device=self.device) self._ALL_INDICES = torch.arange(self.num_instances, dtype=torch.long, device=self.device)
self._ALL_BODY_INDICES = torch.arange(self.body_physx_view.count, dtype=torch.long, device=self.device) self._ALL_BODY_INDICES = torch.arange(
self.root_physx_view.count * self.num_bodies, dtype=torch.long, device=self.device
)
self.GRAVITY_VEC_W = torch.tensor((0.0, 0.0, -1.0), device=self.device).repeat(self.num_instances, 1) self.GRAVITY_VEC_W = torch.tensor((0.0, 0.0, -1.0), device=self.device).repeat(self.num_instances, 1)
self.FORWARD_VEC_B = torch.tensor((1.0, 0.0, 0.0), device=self.device).repeat(self.num_instances, 1) self.FORWARD_VEC_B = torch.tensor((1.0, 0.0, 0.0), device=self.device).repeat(self.num_instances, 1)
# external forces and torques # external forces and torques
...@@ -334,9 +342,12 @@ class RigidObject(AssetBase): ...@@ -334,9 +342,12 @@ class RigidObject(AssetBase):
self._data.body_names = self.body_names self._data.body_names = self.body_names
# -- root states # -- root states
self._data.root_state_w = torch.zeros(self.num_instances, 13, device=self.device) self._data.root_state_w = torch.zeros(self.num_instances, 13, device=self.device)
self._data.root_state_w[:, 3] = 1.0 # set default quaternion to (1, 0, 0, 0)
self._data.default_root_state = torch.zeros_like(self._data.root_state_w) self._data.default_root_state = torch.zeros_like(self._data.root_state_w)
self._data.default_root_state[:, 3] = 1.0 # set default quaternion to (1, 0, 0, 0)
# -- body states # -- body states
self._data.body_state_w = torch.zeros(self.num_instances, self.num_bodies, 13, device=self.device) self._data.body_state_w = torch.zeros(self.num_instances, self.num_bodies, 13, device=self.device)
self._data.body_state_w[:, :, 3] = 1.0 # set default quaternion to (1, 0, 0, 0)
# -- post-computed # -- post-computed
self._data.root_vel_b = torch.zeros(self.num_instances, 6, device=self.device) self._data.root_vel_b = torch.zeros(self.num_instances, 6, device=self.device)
self._data.projected_gravity_b = torch.zeros(self.num_instances, 3, device=self.device) self._data.projected_gravity_b = torch.zeros(self.num_instances, 3, device=self.device)
...@@ -368,10 +379,6 @@ class RigidObject(AssetBase): ...@@ -368,10 +379,6 @@ class RigidObject(AssetBase):
This has been separated from the update function to allow for the child classes to This has been separated from the update function to allow for the child classes to
override the update function without having to worry about updating the common data. override the update function without having to worry about updating the common data.
""" """
# -- body-state (note: we roll the quaternion to match the convention used in Isaac Sim -- wxyz)
self._data.body_state_w[..., :7] = self.body_physx_view.get_transforms().view(-1, self.num_bodies, 7)
self._data.body_state_w[..., 3:7] = math_utils.convert_quat(self._data.body_state_w[..., 3:7], to="wxyz")
self._data.body_state_w[..., 7:] = self.body_physx_view.get_velocities().view(-1, self.num_bodies, 6)
# -- body acceleration # -- body acceleration
self._data.body_acc_w[:] = (self._data.body_state_w[..., 7:] - self._last_body_vel_w) / dt self._data.body_acc_w[:] = (self._data.body_state_w[..., 7:] - self._last_body_vel_w) / dt
self._last_body_vel_w[:] = self._data.body_state_w[..., 7:] self._last_body_vel_w[:] = self._data.body_state_w[..., 7:]
...@@ -398,4 +405,3 @@ class RigidObject(AssetBase): ...@@ -398,4 +405,3 @@ class RigidObject(AssetBase):
# set all existing views to None to invalidate them # set all existing views to None to invalidate them
self._physics_sim_view = None self._physics_sim_view = None
self._root_physx_view = None self._root_physx_view = None
self._body_physx_view = None
...@@ -25,23 +25,23 @@ class RigidObjectData: ...@@ -25,23 +25,23 @@ class RigidObjectData:
## ##
default_root_state: torch.Tensor = None default_root_state: torch.Tensor = None
"""Default root state ``[pos, quat, lin_vel, ang_vel]`` in local environment frame. Shape is (count, 13).""" """Default root state ``[pos, quat, lin_vel, ang_vel]`` in local environment frame. Shape is (num_instances, 13)."""
## ##
# Frame states. # Frame states.
## ##
root_state_w: torch.Tensor = None root_state_w: torch.Tensor = None
"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (count, 13).""" """Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13)."""
root_vel_b: torch.Tensor = None root_vel_b: torch.Tensor = None
"""Root velocity `[lin_vel, ang_vel]` in base frame. Shape is (count, 6).""" """Root velocity `[lin_vel, ang_vel]` in base frame. Shape is (num_instances, 6)."""
projected_gravity_b: torch.Tensor = None projected_gravity_b: torch.Tensor = None
"""Projection of the gravity direction on base frame. Shape is (count, 3).""" """Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""
heading_w: torch.Tensor = None heading_w: torch.Tensor = None
"""Yaw heading of the base frame (in radians). Shape is (count,). """Yaw heading of the base frame (in radians). Shape is (num_instances,).
Note: Note:
This quantity is computed by assuming that the forward-direction of the base This quantity is computed by assuming that the forward-direction of the base
...@@ -50,10 +50,10 @@ class RigidObjectData: ...@@ -50,10 +50,10 @@ class RigidObjectData:
body_state_w: torch.Tensor = None body_state_w: torch.Tensor = None
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame. """State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame.
Shape is (count, num_bodies, 13).""" Shape is (num_instances, num_bodies, 13)."""
body_acc_w: torch.Tensor = None body_acc_w: torch.Tensor = None
"""Acceleration of all bodies. Shape is (count, num_bodies, 6). """Acceleration of all bodies. Shape is (num_instances, num_bodies, 6).
Note: Note:
This quantity is computed based on the rigid body state from the last step. This quantity is computed based on the rigid body state from the last step.
...@@ -65,70 +65,70 @@ class RigidObjectData: ...@@ -65,70 +65,70 @@ class RigidObjectData:
@property @property
def root_pos_w(self) -> torch.Tensor: def root_pos_w(self) -> torch.Tensor:
"""Root position in simulation world frame. Shape is (count, 3).""" """Root position in simulation world frame. Shape is (num_instances, 3)."""
return self.root_state_w[:, :3] return self.root_state_w[:, :3]
@property @property
def root_quat_w(self) -> torch.Tensor: def root_quat_w(self) -> torch.Tensor:
"""Root orientation (w, x, y, z) in simulation world frame. Shape is (count, 4).""" """Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4)."""
return self.root_state_w[:, 3:7] return self.root_state_w[:, 3:7]
@property @property
def root_vel_w(self) -> torch.Tensor: def root_vel_w(self) -> torch.Tensor:
"""Root velocity in simulation world frame. Shape is (count, 6).""" """Root velocity in simulation world frame. Shape is (num_instances, 6)."""
return self.root_state_w[:, 7:13] return self.root_state_w[:, 7:13]
@property @property
def root_lin_vel_w(self) -> torch.Tensor: def root_lin_vel_w(self) -> torch.Tensor:
"""Root linear velocity in simulation world frame. Shape is (count, 3).""" """Root linear velocity in simulation world frame. Shape is (num_instances, 3)."""
return self.root_state_w[:, 7:10] return self.root_state_w[:, 7:10]
@property @property
def root_ang_vel_w(self) -> torch.Tensor: def root_ang_vel_w(self) -> torch.Tensor:
"""Root angular velocity in simulation world frame. Shape is (count, 3).""" """Root angular velocity in simulation world frame. Shape is (num_instances, 3)."""
return self.root_state_w[:, 10:13] return self.root_state_w[:, 10:13]
@property @property
def root_lin_vel_b(self) -> torch.Tensor: def root_lin_vel_b(self) -> torch.Tensor:
"""Root linear velocity in base frame. Shape is (count, 3).""" """Root linear velocity in base frame. Shape is (num_instances, 3)."""
return self.root_vel_b[:, 0:3] return self.root_vel_b[:, 0:3]
@property @property
def root_ang_vel_b(self) -> torch.Tensor: def root_ang_vel_b(self) -> torch.Tensor:
"""Root angular velocity in base world frame. Shape is (count, 3).""" """Root angular velocity in base world frame. Shape is (num_instances, 3)."""
return self.root_vel_b[:, 3:6] return self.root_vel_b[:, 3:6]
@property @property
def body_pos_w(self) -> torch.Tensor: def body_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (count, num_bodies, 3).""" """Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3)."""
return self.body_state_w[..., :3] return self.body_state_w[..., :3]
@property @property
def body_quat_w(self) -> torch.Tensor: def body_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (count, num_bodies, 4).""" """Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4)."""
return self.body_state_w[..., 3:7] return self.body_state_w[..., 3:7]
@property @property
def body_vel_w(self) -> torch.Tensor: def body_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (count, num_bodies, 6).""" """Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6)."""
return self.body_state_w[..., 7:13] return self.body_state_w[..., 7:13]
@property @property
def body_lin_vel_w(self) -> torch.Tensor: def body_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (count, num_bodies, 3).""" """Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3)."""
return self.body_state_w[..., 7:10] return self.body_state_w[..., 7:10]
@property @property
def body_ang_vel_w(self) -> torch.Tensor: def body_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (count, num_bodies, 3).""" """Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3)."""
return self.body_state_w[..., 10:13] return self.body_state_w[..., 10:13]
@property @property
def body_lin_acc_w(self) -> torch.Tensor: def body_lin_acc_w(self) -> torch.Tensor:
"""Linear acceleration of all bodies in simulation world frame. Shape is (count, num_bodies, 3).""" """Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3)."""
return self.body_acc_w[..., 0:3] return self.body_acc_w[..., 0:3]
@property @property
def body_ang_acc_w(self) -> torch.Tensor: def body_ang_acc_w(self) -> torch.Tensor:
"""Angular acceleration of all bodies in simulation world frame. Shape is (count, num_bodies, 3).""" """Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3)."""
return self.body_acc_w[..., 3:6] return self.body_acc_w[..., 3:6]
...@@ -44,46 +44,77 @@ def randomize_rigid_body_material( ...@@ -44,46 +44,77 @@ def randomize_rigid_body_material(
uniform random values from the given ranges. uniform random values from the given ranges.
The material properties are then assigned to the geometries of the asset. The assignment is done by The material properties are then assigned to the geometries of the asset. The assignment is done by
creating a random integer tensor of shape (total_body_count, num_shapes) where ``total_body_count`` creating a random integer tensor of shape (num_instances, max_num_shapes) where ``num_instances``
is the number of assets spawned times the number of bodies per asset and ``num_shapes`` is the number of is the number of assets spawned and ``max_num_shapes`` is the maximum number of shapes in the asset (over
shapes per body. The integer values are used as indices to select the material properties from the all bodies). The integer values are used as indices to select the material properties from the
material buckets. material buckets.
.. tip:: .. attention::
This function uses CPU tensors to assign the material properties. It is recommended to use this function This function uses CPU tensors to assign the material properties. It is recommended to use this function
only during the initialization of the environment. only during the initialization of the environment. Otherwise, it may lead to a significant performance
overhead.
.. note:: .. note::
PhysX only allows 64000 unique physics materials in the scene. If the number of materials exceeds this PhysX only allows 64000 unique physics materials in the scene. If the number of materials exceeds this
limit, the simulation will crash. limit, the simulation will crash.
""" """
# extract the used quantities (to enable type-hinting) # extract the used quantities (to enable type-hinting)
asset: RigidObject = env.scene[asset_cfg.name] asset: RigidObject | Articulation = env.scene[asset_cfg.name]
num_envs = env.scene.num_envs num_envs = env.scene.num_envs
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
env_ids = torch.arange(num_envs, device="cpu") env_ids = torch.arange(num_envs, device="cpu")
# resolve body indices
if isinstance(asset_cfg.body_ids, slice):
body_ids = torch.arange(asset.num_bodies, dtype=torch.int, device="cpu")[asset_cfg.body_ids]
else:
body_ids = torch.tensor(asset_cfg.body_ids, dtype=torch.int, device="cpu")
# sample material properties from the given ranges # sample material properties from the given ranges
material_buckets = torch.zeros(num_buckets, 3) material_buckets = torch.zeros(num_buckets, 3)
material_buckets[:, 0].uniform_(*static_friction_range) material_buckets[:, 0].uniform_(*static_friction_range)
material_buckets[:, 1].uniform_(*dynamic_friction_range) material_buckets[:, 1].uniform_(*dynamic_friction_range)
material_buckets[:, 2].uniform_(*restitution_range) material_buckets[:, 2].uniform_(*restitution_range)
# create random material assignments based on the total number of shapes: num_assets x num_bodies x num_shapes
material_ids = torch.randint(0, num_buckets, (asset.body_physx_view.count, asset.body_physx_view.max_shapes)) # create random material assignments based on the total number of shapes: num_assets x num_shapes
materials = material_buckets[material_ids] # note: not optimal since it creates assignments for all the shapes but only a subset is used in the body indices case.
# resolve the global body indices from the env_ids and the env_body_ids material_ids = torch.randint(0, num_buckets, (len(env_ids), asset.root_physx_view.max_shapes))
bodies_per_env = asset.body_physx_view.count // num_envs # - number of bodies per spawned asset
indices = body_ids.repeat(len(env_ids), 1) if asset_cfg.body_ids == slice(None):
indices += env_ids.unsqueeze(1) * bodies_per_env # get the current materials of the bodies
materials = asset.root_physx_view.get_material_properties()
# assign the new materials
# material ids are of shape: num_env_ids x num_shapes
# material_buckets are of shape: num_buckets x 3
materials[env_ids] = material_buckets[material_ids]
# set the material properties into the physics simulation # set the material properties into the physics simulation
asset.body_physx_view.set_material_properties(materials, indices) asset.root_physx_view.set_material_properties(materials, env_ids)
elif isinstance(asset, Articulation):
# obtain number of shapes per body (needed for indexing the material properties correctly)
# note: this is a workaround since the Articulation does not provide a direct way to obtain the number of shapes
# per body. We use the physics simulation view to obtain the number of shapes per body.
num_shapes_per_body = []
for link_path in asset.root_physx_view.link_paths[0]:
link_physx_view = asset._physics_sim_view.create_rigid_body_view(link_path) # type: ignore
num_shapes_per_body.append(link_physx_view.max_shapes)
# get the current materials of the bodies
materials = asset.root_physx_view.get_material_properties()
# sample material properties from the given ranges
for body_id in asset_cfg.body_ids:
# start index of shape
start_idx = sum(num_shapes_per_body[:body_id])
# end index of shape
end_idx = start_idx + num_shapes_per_body[body_id]
# assign the new materials
# material ids are of shape: num_env_ids x num_shapes
# material_buckets are of shape: num_buckets x 3
materials[env_ids, start_idx:end_idx] = material_buckets[material_ids[:, start_idx:end_idx]]
# set the material properties into the physics simulation
asset.root_physx_view.set_material_properties(materials, env_ids)
else:
raise ValueError(
f"Randomization term 'randomize_rigid_body_material' not supported for asset: '{asset_cfg.name}'"
f" with type: '{type(asset)}' and body_ids: '{asset_cfg.body_ids}'."
)
def add_body_mass( def add_body_mass(
...@@ -96,27 +127,25 @@ def add_body_mass( ...@@ -96,27 +127,25 @@ def add_body_mass(
only during the initialization of the environment. only during the initialization of the environment.
""" """
# extract the used quantities (to enable type-hinting) # extract the used quantities (to enable type-hinting)
asset: RigidObject = env.scene[asset_cfg.name] asset: RigidObject | Articulation = env.scene[asset_cfg.name]
num_envs = env.scene.num_envs num_envs = env.scene.num_envs
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
env_ids = torch.arange(num_envs, device="cpu") env_ids = torch.arange(num_envs, device="cpu")
# resolve body indices # resolve body indices
if isinstance(asset_cfg.body_ids, slice): if asset_cfg.body_ids == slice(None):
body_ids = torch.arange(asset.num_bodies, dtype=torch.int, device="cpu")[asset_cfg.body_ids] body_ids = torch.arange(asset.num_bodies, dtype=torch.int, device="cpu")
else: else:
body_ids = torch.tensor(asset_cfg.body_ids, dtype=torch.int, device="cpu") body_ids = torch.tensor(asset_cfg.body_ids, dtype=torch.int, device="cpu")
# get the current masses of the bodies (num_assets x num_bodies) # get the current masses of the bodies (num_assets, num_bodies)
masses = asset.body_physx_view.get_masses() masses = asset.root_physx_view.get_masses()
masses += sample_uniform(*mass_range, masses.shape, device=masses.device) # note: we modify the masses in-place for all environments
# resolve the global body indices from the env_ids and the env_body_ids # however, the setter takes care that only the masses of the specified environments are modified
bodies_per_env = asset.body_physx_view.count // env.num_envs masses[:, body_ids] += sample_uniform(*mass_range, (masses.shape[0], len(body_ids)), device=masses.device)
indices = body_ids.repeat(len(env_ids), 1)
indices += env_ids.unsqueeze(1) * bodies_per_env
# set the mass into the physics simulation # set the mass into the physics simulation
asset.body_physx_view.set_masses(masses, indices) asset.root_physx_view.set_masses(masses, env_ids)
def apply_external_force_torque( def apply_external_force_torque(
...@@ -134,7 +163,7 @@ def apply_external_force_torque( ...@@ -134,7 +163,7 @@ def apply_external_force_torque(
applied when ``asset.write_data_to_sim()`` is called in the environment. applied when ``asset.write_data_to_sim()`` is called in the environment.
""" """
# extract the used quantities (to enable type-hinting) # extract the used quantities (to enable type-hinting)
asset: RigidObject = env.scene[asset_cfg.name] asset: RigidObject | Articulation = env.scene[asset_cfg.name]
num_envs = env.scene.num_envs num_envs = env.scene.num_envs
# resolve environment ids # resolve environment ids
if env_ids is None: if env_ids is None:
......
...@@ -87,5 +87,4 @@ class InteractiveSceneCfg: ...@@ -87,5 +87,4 @@ class InteractiveSceneCfg:
""" """
replicate_physics: bool = True replicate_physics: bool = True
"""Enable/disable replication of physics schemas when using the Cloner APIs. Default is True. """Enable/disable replication of physics schemas when using the Cloner APIs. Default is True."""
"""
...@@ -86,6 +86,19 @@ class TestArticulation(unittest.TestCase): ...@@ -86,6 +86,19 @@ class TestArticulation(unittest.TestCase):
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertTrue(robot.data.root_quat_w.shape == (1, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 21)) self.assertTrue(robot.data.joint_pos.shape == (1, 21))
# Check some internal physx data for debugging
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count)
# -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Check that the body_physx_view is deprecated
with self.assertWarns(DeprecationWarning):
robot.body_physx_view
# Simulate physics # Simulate physics
for _ in range(10): for _ in range(10):
# perform rendering # perform rendering
...@@ -112,6 +125,19 @@ class TestArticulation(unittest.TestCase): ...@@ -112,6 +125,19 @@ class TestArticulation(unittest.TestCase):
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertTrue(robot.data.root_quat_w.shape == (1, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 12)) self.assertTrue(robot.data.joint_pos.shape == (1, 12))
# Check some internal physx data for debugging
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count)
# -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Check that the body_physx_view is deprecated
with self.assertWarns(DeprecationWarning):
robot.body_physx_view
# Simulate physics # Simulate physics
for _ in range(10): for _ in range(10):
# perform rendering # perform rendering
...@@ -138,6 +164,19 @@ class TestArticulation(unittest.TestCase): ...@@ -138,6 +164,19 @@ class TestArticulation(unittest.TestCase):
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertTrue(robot.data.root_quat_w.shape == (1, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 9)) self.assertTrue(robot.data.joint_pos.shape == (1, 9))
# Check some internal physx data for debugging
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count)
# -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Check that the body_physx_view is deprecated
with self.assertWarns(DeprecationWarning):
robot.body_physx_view
# Simulate physics # Simulate physics
for _ in range(10): for _ in range(10):
# perform rendering # perform rendering
...@@ -176,6 +215,19 @@ class TestArticulation(unittest.TestCase): ...@@ -176,6 +215,19 @@ class TestArticulation(unittest.TestCase):
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertTrue(robot.data.root_quat_w.shape == (1, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 1)) self.assertTrue(robot.data.joint_pos.shape == (1, 1))
# Check some internal physx data for debugging
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count)
# -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Check that the body_physx_view is deprecated
with self.assertWarns(DeprecationWarning):
robot.body_physx_view
# Simulate physics # Simulate physics
for _ in range(10): for _ in range(10):
# perform rendering # perform rendering
......
...@@ -219,7 +219,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -219,7 +219,7 @@ class TestRigidObject(unittest.TestCase):
# assert that set root quantities are equal to the ones set in the state_dict # assert that set root quantities are equal to the ones set in the state_dict
for key, expected_value in state_dict.items(): for key, expected_value in state_dict.items():
value = getattr(cube_object.data, key) value = getattr(cube_object.data, key)
torch.testing.assert_allclose(value, expected_value, rtol=1e-5, atol=1e-5) torch.testing.assert_close(value, expected_value, rtol=1e-5, atol=1e-5)
cube_object.update(sim.cfg.dt) cube_object.update(sim.cfg.dt)
...@@ -282,7 +282,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -282,7 +282,7 @@ class TestRigidObject(unittest.TestCase):
indices = torch.tensor(range(num_cubes), dtype=torch.int) indices = torch.tensor(range(num_cubes), dtype=torch.int)
# Add friction to cube # Add friction to cube
cube_object.body_physx_view.set_material_properties(materials, indices) cube_object.root_physx_view.set_material_properties(materials, indices)
# Simulate physics # Simulate physics
# perform rendering # perform rendering
...@@ -291,7 +291,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -291,7 +291,7 @@ class TestRigidObject(unittest.TestCase):
cube_object.update(sim.cfg.dt) cube_object.update(sim.cfg.dt)
# Get material properties # Get material properties
materials_to_check = cube_object.body_physx_view.get_material_properties() materials_to_check = cube_object.root_physx_view.get_material_properties()
# Check if material properties are set correctly # Check if material properties are set correctly
torch.testing.assert_close(materials_to_check.reshape(num_cubes, 3), materials) torch.testing.assert_close(materials_to_check.reshape(num_cubes, 3), materials)
...@@ -325,7 +325,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -325,7 +325,7 @@ class TestRigidObject(unittest.TestCase):
cube_object_materials = torch.cat([static_friction, dynamic_friction, restitution], dim=-1) cube_object_materials = torch.cat([static_friction, dynamic_friction, restitution], dim=-1)
indices = torch.tensor(range(num_cubes), dtype=torch.int) indices = torch.tensor(range(num_cubes), dtype=torch.int)
cube_object.body_physx_view.set_material_properties(cube_object_materials, indices) cube_object.root_physx_view.set_material_properties(cube_object_materials, indices)
# Set initial velocity # Set initial velocity
# Initial velocity in X to get the block moving # Initial velocity in X to get the block moving
...@@ -388,7 +388,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -388,7 +388,7 @@ class TestRigidObject(unittest.TestCase):
indices = torch.tensor(range(num_cubes), dtype=torch.int) indices = torch.tensor(range(num_cubes), dtype=torch.int)
# Add friction to cube # Add friction to cube
cube_object.body_physx_view.set_material_properties(cube_object_materials, indices) cube_object.root_physx_view.set_material_properties(cube_object_materials, indices)
# 2 cases: force applied is below and above mu # 2 cases: force applied is below and above mu
# below mu: block should not move as the force applied is <= mu # below mu: block should not move as the force applied is <= mu
...@@ -490,7 +490,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -490,7 +490,7 @@ class TestRigidObject(unittest.TestCase):
) )
# Add friction to cube # Add friction to cube
cube_object.body_physx_view.set_material_properties(cube_object_materials, indices) cube_object.root_physx_view.set_material_properties(cube_object_materials, indices)
curr_z_velocity = cube_object.data.root_lin_vel_w[:, 2] curr_z_velocity = cube_object.data.root_lin_vel_w[:, 2]
...@@ -535,7 +535,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -535,7 +535,7 @@ class TestRigidObject(unittest.TestCase):
sim.reset() sim.reset()
# Get masses before increasing # Get masses before increasing
original_masses = cube_object.body_physx_view.get_masses() original_masses = cube_object.root_physx_view.get_masses()
self.assertEqual(original_masses.shape, (num_cubes, 1)) self.assertEqual(original_masses.shape, (num_cubes, 1))
...@@ -545,9 +545,9 @@ class TestRigidObject(unittest.TestCase): ...@@ -545,9 +545,9 @@ class TestRigidObject(unittest.TestCase):
indices = torch.tensor(range(num_cubes), dtype=torch.int) indices = torch.tensor(range(num_cubes), dtype=torch.int)
# Add friction to cube # Add friction to cube
cube_object.body_physx_view.set_masses(masses, indices) cube_object.root_physx_view.set_masses(masses, indices)
torch.testing.assert_close(cube_object.body_physx_view.get_masses(), masses) torch.testing.assert_close(cube_object.root_physx_view.get_masses(), masses)
# Simulate physics # Simulate physics
# perform rendering # perform rendering
...@@ -555,7 +555,7 @@ class TestRigidObject(unittest.TestCase): ...@@ -555,7 +555,7 @@ class TestRigidObject(unittest.TestCase):
# update object # update object
cube_object.update(sim.cfg.dt) cube_object.update(sim.cfg.dt)
masses_to_check = cube_object.body_physx_view.get_masses() masses_to_check = cube_object.root_physx_view.get_masses()
# Check if mass is set correctly # Check if mass is set correctly
torch.testing.assert_close(masses, masses_to_check) torch.testing.assert_close(masses, masses_to_check)
......
...@@ -179,7 +179,7 @@ class CartpoleEnvCfg(RLTaskEnvCfg): ...@@ -179,7 +179,7 @@ class CartpoleEnvCfg(RLTaskEnvCfg):
"""Configuration for the locomotion velocity-tracking environment.""" """Configuration for the locomotion velocity-tracking environment."""
# Scene settings # Scene settings
scene: CartpoleSceneCfg = CartpoleSceneCfg(num_envs=4096, env_spacing=4.0, replicate_physics=True) scene: CartpoleSceneCfg = CartpoleSceneCfg(num_envs=4096, env_spacing=4.0)
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
......
...@@ -184,7 +184,7 @@ class QuadrupedEnvCfg(BaseEnvCfg): ...@@ -184,7 +184,7 @@ class QuadrupedEnvCfg(BaseEnvCfg):
"""Configuration for the locomotion velocity-tracking environment.""" """Configuration for the locomotion velocity-tracking environment."""
# Scene settings # Scene settings
scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5, replicate_physics=True) scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5)
# Basic settings # Basic settings
observations: ObservationsCfg = ObservationsCfg() observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg() actions: ActionsCfg = ActionsCfg()
......
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