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

Optimizes getters of data inside asset classes (#2118)

# Description

Previously the root positions was obtained by performing the following
steps:

1. Call PhysX getters to get transforms and velocities
2. Concatenating the two to make a single state tensor
3. Indexing this tensor to get the position

For applications where we only want the positions, the above is an
expensive operation as we call CUDA-MemCpy twice and then do
concatenation which adds overhead.

This MR simplifies the above process by having separate lazy buffers for
poses, velocities and states.

Fixes # (issue)

<!-- As a practice, it is recommended to open an issue to have
discussions on the proposed pull request.
This makes it easier for the community to keep track of what is being
developed or added, and if a given feature
is demanded by more than one party. -->

## Type of change

- New feature (non-breaking change which adds functionality)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- This change requires a documentation update

## Screenshots

Please attach before and after screenshots of the change if applicable.

<!--
Example:

| Before | After |
| ------ | ----- |
| _gif/png before_ | _gif/png after_ |

To upload images to a PR -- simply drag and drop an image while in edit
mode and it should upload the image directly. You can then paste that
source into the above before/after sections.
-->

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

---------
Signed-off-by: 's avatarKelly Guo <kellyg@nvidia.com>
Co-authored-by: 's avatarKelly Guo <kellyg@nvidia.com>
parent d2a41266
......@@ -125,7 +125,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, RigidObj
cone_object.update(sim_dt)
# print the root position
if count % 50 == 0:
print(f"Root position (in world): {cone_object.data.root_state_w[:, :3]}")
print(f"Root position (in world): {cone_object.data.root_pos_w}")
def main():
......
......@@ -165,8 +165,8 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
else:
# obtain quantities from simulation
jacobian = robot.root_physx_view.get_jacobians()[:, ee_jacobi_idx, :, robot_entity_cfg.joint_ids]
ee_pose_w = robot.data.body_state_w[:, robot_entity_cfg.body_ids[0], 0:7]
root_pose_w = robot.data.root_state_w[:, 0:7]
ee_pose_w = robot.data.body_pose_w[:, robot_entity_cfg.body_ids[0]]
root_pose_w = robot.data.root_pose_w
joint_pos = robot.data.joint_pos[:, robot_entity_cfg.joint_ids]
# compute frame in root frame
ee_pos_b, ee_quat_b = subtract_frame_transforms(
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.40.2"
version = "0.40.3"
# Description
title = "Isaac Lab framework for Robot Learning"
......
Changelog
---------
0.40.3 (2025-03-20)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Made separate data buffers for poses and velocities for the :class:`~isaaclab.assets.Articulation`,
:class:`~isaaclab.assets.RigidObject`, and :class:`~isaaclab.assets.RigidObjectCollection` classes.
Previously, the two data buffers were stored together in a single buffer requiring an additional
concatenation operation when accessing the data.
* Cleaned up ordering of members inside the data classes for the assets to make them easier
to comprehend. This reduced the code duplication within the class and made the class
more readable.
0.40.2 (2025-05-10)
~~~~~~~~~~~~~~~~~~~
......
......@@ -286,10 +286,8 @@ class Articulation(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# 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)
self.write_root_link_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_com_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
def write_root_com_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass state over selected environment indices into the simulation.
......@@ -301,7 +299,6 @@ class Articulation(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# set into simulation
self.write_root_com_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_com_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
......@@ -315,7 +312,6 @@ class Articulation(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# set into simulation
self.write_root_link_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_link_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
......@@ -328,23 +324,7 @@ class Articulation(AssetBase):
root_pose: Root poses in simulation frame. Shape is (len(env_ids), 7).
env_ids: Environment indices. If None, then all indices are used.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, :7] = root_pose.clone()
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_state_w[:, :7].clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
# Need to invalidate the buffer to trigger the update with the new root pose.
self._data._body_state_w.timestamp = -1.0
self._data._body_link_state_w.timestamp = -1.0
self._data._body_com_state_w.timestamp = -1.0
# set into simulation
self.root_physx_view.set_root_transforms(root_poses_xyzw, indices=physx_env_ids)
self.write_root_link_pose_to_sim(root_pose, env_ids=env_ids)
def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root link pose over selected environment indices into the simulation.
......@@ -360,17 +340,27 @@ class Articulation(AssetBase):
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_link_state_w[env_ids, :7] = root_pose.clone()
self._data.root_state_w[env_ids, :7] = self._data.root_link_state_w[env_ids, :7]
self._data.root_link_pose_w[env_ids] = root_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_link_state_w.data is not None:
self._data.root_link_state_w[env_ids, :7] = self._data.root_link_pose_w[env_ids]
if self._data._root_state_w.data is not None:
self._data.root_state_w[env_ids, :7] = self._data.root_link_pose_w[env_ids]
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_link_state_w[:, :7].clone()
root_poses_xyzw = self._data.root_link_pose_w.clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
# Need to invalidate the buffer to trigger the update with the new root pose.
# Need to invalidate the buffer to trigger the update with the new state.
self._data._body_link_pose_w.timestamp = -1.0
self._data._body_com_pose_w.timestamp = -1.0
self._data._body_state_w.timestamp = -1.0
self._data._body_link_state_w.timestamp = -1.0
self._data._body_com_state_w.timestamp = -1.0
# set into simulation
self.root_physx_view.set_root_transforms(root_poses_xyzw, indices=physx_env_ids)
......@@ -385,23 +375,31 @@ class Articulation(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
com_pos = self.data.com_pos_b[env_ids, 0, :]
com_quat = self.data.com_quat_b[env_ids, 0, :]
local_env_ids = slice(env_ids)
else:
local_env_ids = env_ids
# set into internal buffers
self._data.root_com_pose_w[local_env_ids] = root_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_com_state_w.data is not None:
self._data.root_com_state_w[local_env_ids, :7] = self._data.root_com_pose_w[local_env_ids]
# get CoM pose in link frame
com_pos_b = self.data.body_com_pos_b[local_env_ids, 0, :]
com_quat_b = self.data.body_com_quat_b[local_env_ids, 0, :]
# transform input CoM pose to link frame
root_link_pos, root_link_quat = math_utils.combine_frame_transforms(
root_pose[..., :3],
root_pose[..., 3:7],
math_utils.quat_apply(math_utils.quat_inv(com_quat), -com_pos),
math_utils.quat_inv(com_quat),
math_utils.quat_apply(math_utils.quat_inv(com_quat_b), -com_pos_b),
math_utils.quat_inv(com_quat_b),
)
root_link_pose = torch.cat((root_link_pos, root_link_quat), dim=-1)
self.write_root_link_pose_to_sim(root_pose=root_link_pose, env_ids=physx_env_ids)
# write transformed pose in link frame to sim
self.write_root_link_pose_to_sim(root_pose=root_link_pose, env_ids=env_ids)
def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass velocity over selected environment indices into the simulation.
......@@ -413,17 +411,7 @@ class Articulation(AssetBase):
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.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
self._data.body_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_root_velocities(self._data.root_state_w[:, 7:], indices=physx_env_ids)
self.write_root_com_velocity_to_sim(root_velocity=root_velocity, env_ids=env_ids)
def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass velocity over selected environment indices into the simulation.
......@@ -435,19 +423,25 @@ class Articulation(AssetBase):
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.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_com_state_w[env_ids, 7:] = root_velocity.clone()
self._data.root_state_w[env_ids, 7:] = self._data.root_com_state_w[env_ids, 7:]
self._data.root_com_vel_w[env_ids] = root_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_com_state_w.data is not None:
self._data.root_com_state_w[env_ids, 7:] = self._data.root_com_vel_w[env_ids]
if self._data._root_state_w.data is not None:
self._data.root_state_w[env_ids, 7:] = self._data.root_com_vel_w[env_ids]
# make the acceleration zero to prevent reporting old values
self._data.body_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_root_velocities(self._data.root_com_state_w[:, 7:], indices=physx_env_ids)
self.root_physx_view.set_root_velocities(self._data.root_com_vel_w, indices=physx_env_ids)
def write_root_link_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root link velocity over selected environment indices into the simulation.
......@@ -460,20 +454,28 @@ class Articulation(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
local_env_ids = slice(env_ids)
else:
local_env_ids = env_ids
# set into internal buffers
self._data.root_link_vel_w[local_env_ids] = root_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_link_state_w.data is not None:
self._data.root_link_state_w[local_env_ids, 7:] = self._data.root_link_vel_w[local_env_ids]
# get CoM pose in link frame
quat = self.data.root_link_quat_w[local_env_ids]
com_pos_b = self.data.body_com_pos_b[local_env_ids, 0, :]
# transform input velocity to center of mass frame
root_com_velocity = root_velocity.clone()
quat = self.data.root_link_state_w[env_ids, 3:7]
com_pos_b = self.data.com_pos_b[env_ids, 0, :]
# transform given velocity to center of mass
root_com_velocity[:, :3] += torch.linalg.cross(
root_com_velocity[:, 3:], math_utils.quat_apply(quat, com_pos_b), dim=-1
)
# write center of mass velocity to sim
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity, env_ids=physx_env_ids)
# write transformed velocity in CoM frame to sim
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity, env_ids=env_ids)
def write_joint_state_to_sim(
self,
......
......@@ -69,16 +69,30 @@ class ArticulationData:
self._previous_joint_vel = self._root_physx_view.get_dof_velocities().clone()
# Initialize the lazy buffers.
# -- link frame w.r.t. world frame
self._root_link_pose_w = TimestampedBuffer()
self._root_link_vel_w = TimestampedBuffer()
self._body_link_pose_w = TimestampedBuffer()
self._body_link_vel_w = TimestampedBuffer()
# -- com frame w.r.t. link frame
self._body_com_pose_b = TimestampedBuffer()
# -- com frame w.r.t. world frame
self._root_com_pose_w = TimestampedBuffer()
self._root_com_vel_w = TimestampedBuffer()
self._body_com_pose_w = TimestampedBuffer()
self._body_com_vel_w = TimestampedBuffer()
self._body_com_acc_w = TimestampedBuffer()
# -- combined state (these are cached as they concatenate)
self._root_state_w = TimestampedBuffer()
self._root_link_state_w = TimestampedBuffer()
self._root_com_state_w = TimestampedBuffer()
self._body_state_w = TimestampedBuffer()
self._body_link_state_w = TimestampedBuffer()
self._body_com_state_w = TimestampedBuffer()
self._body_acc_w = TimestampedBuffer()
# -- joint state
self._joint_pos = TimestampedBuffer()
self._joint_acc = TimestampedBuffer()
self._joint_vel = TimestampedBuffer()
self._joint_acc = TimestampedBuffer()
self._body_incoming_joint_wrench_b = TimestampedBuffer()
def update(self, dt: float):
......@@ -365,9 +379,77 @@ class ArticulationData:
"""Fixed tendon position limits provided to the simulation. Shape is (num_instances, num_fixed_tendons, 2)."""
##
# Properties.
# Root state properties.
##
@property
def root_link_pose_w(self) -> torch.Tensor:
"""Root link pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 7).
This quantity is the pose of the articulation root's actor frame relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._root_link_pose_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_root_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
# set the buffer data and timestamp
self._root_link_pose_w.data = pose
self._root_link_pose_w.timestamp = self._sim_timestamp
return self._root_link_pose_w.data
@property
def root_link_vel_w(self) -> torch.Tensor:
"""Root link velocity ``[lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the articulation root's actor frame
relative to the world.
"""
if self._root_link_vel_w.timestamp < self._sim_timestamp:
# read the CoM velocity
vel = self.root_com_vel_w.clone()
# adjust linear velocity to link from center of mass
vel[:, :3] += torch.linalg.cross(
vel[:, 3:], math_utils.quat_rotate(self.root_link_quat_w, -self.body_com_pos_b[:, 0]), dim=-1
)
# set the buffer data and timestamp
self._root_link_vel_w.data = vel
self._root_link_vel_w.timestamp = self._sim_timestamp
return self._root_link_vel_w.data
@property
def root_com_pose_w(self) -> torch.Tensor:
"""Root center of mass pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 7).
This quantity is the pose of the articulation root's center of mass frame relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._root_com_pose_w.timestamp < self._sim_timestamp:
# apply local transform to center of mass frame
pos, quat = math_utils.combine_frame_transforms(
self.root_link_pos_w, self.root_link_quat_w, self.body_com_pos_b[:, 0], self.body_com_quat_b[:, 0]
)
# set the buffer data and timestamp
self._root_com_pose_w.data = torch.cat((pos, quat), dim=-1)
self._root_com_pose_w.timestamp = self._sim_timestamp
return self._root_com_pose_w.data
@property
def root_com_vel_w(self) -> torch.Tensor:
"""Root center of mass velocity ``[lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the articulation root's center of mass frame
relative to the world.
"""
if self._root_com_vel_w.timestamp < self._sim_timestamp:
self._root_com_vel_w.data = self._root_physx_view.get_root_velocities()
self._root_com_vel_w.timestamp = self._sim_timestamp
return self._root_com_vel_w.data
@property
def root_state_w(self):
"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13).
......@@ -376,13 +458,9 @@ class ArticulationData:
the linear and angular velocities are of the articulation root's center of mass frame.
"""
if self._root_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_root_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_root_velocities()
# set the buffer data and timestamp
self._root_state_w.data = torch.cat((pose, velocity), dim=-1)
self._root_state_w.data = torch.cat((self.root_link_pose_w, self.root_com_vel_w), dim=-1)
self._root_state_w.timestamp = self._sim_timestamp
return self._root_state_w.data
@property
......@@ -393,17 +471,7 @@ class ArticulationData:
world.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_root_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_root_velocities().clone()
# adjust linear velocity to link from center of mass
velocity[:, :3] += torch.linalg.cross(
velocity[:, 3:], math_utils.quat_apply(pose[:, 3:7], -self.com_pos_b[:, 0, :]), dim=-1
)
# set the buffer data and timestamp
self._root_link_state_w.data = torch.cat((pose, velocity), dim=-1)
self._root_link_state_w.data = torch.cat((self.root_link_pose_w, self.root_link_vel_w), dim=-1)
self._root_link_state_w.timestamp = self._sim_timestamp
return self._root_link_state_w.data
......@@ -417,39 +485,101 @@ class ArticulationData:
orientation of the principle inertia.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
pose = self._root_physx_view.get_root_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_root_velocities()
self._root_com_state_w.data = torch.cat((self.root_com_pose_w, self.root_com_vel_w), dim=-1)
self._root_com_state_w.timestamp = self._sim_timestamp
return self._root_com_state_w.data
##
# Body state properties.
##
@property
def body_link_pose_w(self) -> torch.Tensor:
"""Body link pose ``[pos, quat]`` in simulation world frame.
Shape is (num_instances, num_bodies, 7).
This quantity is the pose of the articulation links' actor frame relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._body_link_pose_w.timestamp < self._sim_timestamp:
# perform forward kinematics (shouldn't cause overhead if it happened already)
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
poses = self._root_physx_view.get_link_transforms().clone()
poses[..., 3:7] = math_utils.convert_quat(poses[..., 3:7], to="wxyz")
# set the buffer data and timestamp
self._body_link_pose_w.data = poses
self._body_link_pose_w.timestamp = self._sim_timestamp
return self._body_link_pose_w.data
@property
def body_link_vel_w(self) -> torch.Tensor:
"""Body link velocity ``[lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, num_bodies, 6).
This quantity contains the linear and angular velocities of the articulation links' actor frame
relative to the world.
"""
if self._body_link_vel_w.timestamp < self._sim_timestamp:
# read data from simulation
velocities = self.body_com_vel_w.clone()
# adjust linear velocity to link from center of mass
velocities[..., :3] += torch.linalg.cross(
velocities[..., 3:], math_utils.quat_rotate(self.body_link_quat_w, -self.body_com_pos_b), dim=-1
)
# set the buffer data and timestamp
self._body_link_vel_w.data = velocities
self._body_link_vel_w.timestamp = self._sim_timestamp
return self._body_link_vel_w.data
# adjust pose to center of mass
@property
def body_com_pose_w(self) -> torch.Tensor:
"""Body center of mass pose ``[pos, quat]`` in simulation world frame.
Shape is (num_instances, num_bodies, 7).
This quantity is the pose of the center of mass frame of the articulation links relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._body_com_pose_w.timestamp < self._sim_timestamp:
# apply local transform to center of mass frame
pos, quat = math_utils.combine_frame_transforms(
pose[:, :3], pose[:, 3:7], self.com_pos_b[:, 0, :], self.com_quat_b[:, 0, :]
self.body_link_pos_w, self.body_link_quat_w, self.body_com_pos_b, self.body_com_quat_b
)
pose = torch.cat((pos, quat), dim=-1)
# set the buffer data and timestamp
self._root_com_state_w.data = torch.cat((pose, velocity), dim=-1)
self._root_com_state_w.timestamp = self._sim_timestamp
return self._root_com_state_w.data
self._body_com_pose_w.data = torch.cat((pos, quat), dim=-1)
self._body_com_pose_w.timestamp = self._sim_timestamp
return self._body_com_pose_w.data
@property
def body_com_vel_w(self) -> torch.Tensor:
"""Body center of mass velocity ``[lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, num_bodies, 6).
This quantity contains the linear and angular velocities of the articulation links' center of mass frame
relative to the world.
"""
if self._body_com_vel_w.timestamp < self._sim_timestamp:
self._body_com_vel_w.data = self._root_physx_view.get_link_velocities()
self._body_com_vel_w.timestamp = self._sim_timestamp
return self._body_com_vel_w.data
@property
def body_state_w(self):
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame.
Shape is (num_instances, num_bodies, 13).
The position and quaternion are of all the articulation links's actor frame. Meanwhile, the linear and angular
The position and quaternion are of all the articulation links' actor frame. Meanwhile, the linear and angular
velocities are of the articulation links's center of mass frame.
"""
if self._body_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
poses = self._root_physx_view.get_link_transforms().clone()
poses[..., 3:7] = math_utils.convert_quat(poses[..., 3:7], to="wxyz")
velocities = self._root_physx_view.get_link_velocities()
# set the buffer data and timestamp
self._body_state_w.data = torch.cat((poses, velocities), dim=-1)
self._body_state_w.data = torch.cat((self.body_link_pose_w, self.body_com_vel_w), dim=-1)
self._body_state_w.timestamp = self._sim_timestamp
return self._body_state_w.data
@property
......@@ -460,18 +590,7 @@ class ArticulationData:
The position, quaternion, and linear/angular velocity are of the body's link frame relative to the world.
"""
if self._body_link_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
pose = self._root_physx_view.get_link_transforms().clone()
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
velocity = self._root_physx_view.get_link_velocities()
# adjust linear velocity to link from center of mass
velocity[..., :3] += torch.linalg.cross(
velocity[..., 3:], math_utils.quat_apply(pose[..., 3:7], -self.com_pos_b), dim=-1
)
# set the buffer data and timestamp
self._body_link_state_w.data = torch.cat((pose, velocity), dim=-1)
self._body_link_state_w.data = torch.cat((self.body_link_pose_w, self.body_link_vel_w), dim=-1)
self._body_link_state_w.timestamp = self._sim_timestamp
return self._body_link_state_w.data
......@@ -486,34 +605,42 @@ class ArticulationData:
principle inertia.
"""
if self._body_com_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation (pose is of link)
pose = self._root_physx_view.get_link_transforms().clone()
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
velocity = self._root_physx_view.get_link_velocities()
# adjust pose to center of mass
pos, quat = math_utils.combine_frame_transforms(
pose[..., :3], pose[..., 3:7], self.com_pos_b, self.com_quat_b
)
pose = torch.cat((pos, quat), dim=-1)
# set the buffer data and timestamp
self._body_com_state_w.data = torch.cat((pose, velocity), dim=-1)
self._body_com_state_w.data = torch.cat((self.body_com_pose_w, self.body_com_vel_w), dim=-1)
self._body_com_state_w.timestamp = self._sim_timestamp
return self._body_com_state_w.data
@property
def body_acc_w(self):
"""Acceleration of all bodies (center of mass). Shape is (num_instances, num_bodies, 6).
def body_com_acc_w(self):
"""Acceleration of all bodies center of mass ``[lin_acc, ang_acc]``.
Shape is (num_instances, num_bodies, 6).
All values are relative to the world.
"""
if self._body_acc_w.timestamp < self._sim_timestamp:
if self._body_com_acc_w.timestamp < self._sim_timestamp:
# read data from simulation and set the buffer data and timestamp
self._body_acc_w.data = self._root_physx_view.get_link_accelerations()
self._body_com_acc_w.data = self._root_physx_view.get_link_accelerations()
self._body_com_acc_w.timestamp = self._sim_timestamp
return self._body_com_acc_w.data
@property
def body_com_pose_b(self) -> torch.Tensor:
"""Center of mass pose ``[pos, quat]`` of all bodies in their respective body's link frames.
Shape is (num_instances, 1, 7).
This quantity is the pose of the center of mass frame of the rigid body relative to the body's link frame.
The orientation is provided in (w, x, y, z) format.
"""
if self._body_com_pose_b.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_coms().to(self.device)
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
# set the buffer data and timestamp
self._body_com_pose_b.data = pose
self._body_com_pose_b.timestamp = self._sim_timestamp
self._body_acc_w.timestamp = self._sim_timestamp
return self._body_acc_w.data
return self._body_com_pose_b.data
@property
def body_incoming_joint_wrench_b(self) -> torch.Tensor:
......@@ -531,21 +658,9 @@ class ArticulationData:
self._body_incoming_joint_wrench_b.time_stamp = self._sim_timestamp
return self._body_incoming_joint_wrench_b.data
@property
def projected_gravity_b(self):
"""Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.GRAVITY_VEC_W)
@property
def heading_w(self):
"""Yaw heading of the base frame (in radians). Shape is (num_instances,).
Note:
This quantity is computed by assuming that the forward-direction of the base
frame is along x-direction, i.e. :math:`(1, 0, 0)`.
"""
forward_w = math_utils.quat_apply(self.root_link_quat_w, self.FORWARD_VEC_B)
return torch.atan2(forward_w[:, 1], forward_w[:, 0])
##
# Joint state properties.
##
@property
def joint_pos(self):
......@@ -578,70 +693,63 @@ class ArticulationData:
return self._joint_acc.data
##
# Derived properties.
# Derived Properties.
##
@property
def root_pos_w(self) -> torch.Tensor:
"""Root position in simulation world frame. Shape is (num_instances, 3).
This quantity is the position of the actor frame of the articulation root relative to the world.
"""
return self.root_state_w[:, :3]
@property
def root_quat_w(self) -> torch.Tensor:
"""Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4).
This quantity is the orientation of the actor frame of the articulation root relative to the world.
"""
return self.root_state_w[:, 3:7]
def projected_gravity_b(self):
"""Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.GRAVITY_VEC_W)
@property
def root_vel_w(self) -> torch.Tensor:
"""Root velocity in simulation world frame. Shape is (num_instances, 6).
def heading_w(self):
"""Yaw heading of the base frame (in radians). Shape is (num_instances,).
This quantity contains the linear and angular velocities of the articulation root's center of mass frame
relative to the world.
Note:
This quantity is computed by assuming that the forward-direction of the base
frame is along x-direction, i.e. :math:`(1, 0, 0)`.
"""
return self.root_state_w[:, 7:13]
forward_w = math_utils.quat_apply(self.root_link_quat_w, self.FORWARD_VEC_B)
return torch.atan2(forward_w[:, 1], forward_w[:, 0])
@property
def root_lin_vel_w(self) -> torch.Tensor:
"""Root linear velocity in simulation world frame. Shape is (num_instances, 3).
def root_link_lin_vel_b(self) -> torch.Tensor:
"""Root link linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the articulation root's center of mass frame relative to the world.
This quantity is the linear velocity of the articulation root's actor frame with respect to the
its actor frame.
"""
return self.root_state_w[:, 7:10]
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_lin_vel_w)
@property
def root_ang_vel_w(self) -> torch.Tensor:
"""Root angular velocity in simulation world frame. Shape is (num_instances, 3).
def root_link_ang_vel_b(self) -> torch.Tensor:
"""Root link angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the articulation root's center of mass frame relative to the world.
This quantity is the angular velocity of the articulation root's actor frame with respect to the
its actor frame.
"""
return self.root_state_w[:, 10:13]
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_ang_vel_w)
@property
def root_lin_vel_b(self) -> torch.Tensor:
"""Root linear velocity in base frame. Shape is (num_instances, 3).
def root_com_lin_vel_b(self) -> torch.Tensor:
"""Root center of mass linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the articulation root's center of mass frame relative to the world
with respect to the articulation root's actor frame.
This quantity is the linear velocity of the articulation root's center of mass frame with respect to the
its actor frame.
"""
return math_utils.quat_apply_inverse(self.root_quat_w, self.root_lin_vel_w)
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_lin_vel_w)
@property
def root_ang_vel_b(self) -> torch.Tensor:
"""Root angular velocity in base world frame. Shape is (num_instances, 3).
def root_com_ang_vel_b(self) -> torch.Tensor:
"""Root center of mass angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the articulation root's center of mass frame relative to the world with
respect to the articulation root's actor frame.
This quantity is the angular velocity of the articulation root's center of mass frame with respect to the
its actor frame.
"""
return math_utils.quat_apply_inverse(self.root_quat_w, self.root_ang_vel_w)
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_ang_vel_w)
##
# Derived Root Link Frame Properties
# Sliced properties.
##
@property
......@@ -650,11 +758,7 @@ class ArticulationData:
This quantity is the position of the actor frame of the root rigid body relative to the world.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
pose = self._root_physx_view.get_root_transforms()
return pose[:, :3]
return self.root_link_state_w[:, :3]
return self.root_link_pose_w[:, :3]
@property
def root_link_quat_w(self) -> torch.Tensor:
......@@ -662,21 +766,7 @@ class ArticulationData:
This quantity is the orientation of the actor frame of the root rigid body.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
pose = self._root_physx_view.get_root_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
return pose[:, 3:7]
return self.root_link_state_w[:, 3:7]
@property
def root_link_vel_w(self) -> torch.Tensor:
"""Root link velocity in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the actor frame of the root
rigid body relative to the world.
"""
return self.root_link_state_w[:, 7:13]
return self.root_link_pose_w[:, 3:7]
@property
def root_link_lin_vel_w(self) -> torch.Tensor:
......@@ -684,7 +774,7 @@ class ArticulationData:
This quantity is the linear velocity of the root rigid body's actor frame relative to the world.
"""
return self.root_link_state_w[:, 7:10]
return self.root_link_vel_w[:, :3]
@property
def root_link_ang_vel_w(self) -> torch.Tensor:
......@@ -692,29 +782,7 @@ class ArticulationData:
This quantity is the angular velocity of the actor frame of the root rigid body relative to the world.
"""
return self.root_link_state_w[:, 10:13]
@property
def root_link_lin_vel_b(self) -> torch.Tensor:
"""Root link linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_lin_vel_w)
@property
def root_link_ang_vel_b(self) -> torch.Tensor:
"""Root link angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_ang_vel_w)
##
# Root Center of Mass state properties
##
return self.root_link_vel_w[:, 3:6]
@property
def root_com_pos_w(self) -> torch.Tensor:
......@@ -722,7 +790,7 @@ class ArticulationData:
This quantity is the position of the actor frame of the root rigid body relative to the world.
"""
return self.root_com_state_w[:, :3]
return self.root_com_pose_w[:, :3]
@property
def root_com_quat_w(self) -> torch.Tensor:
......@@ -730,19 +798,7 @@ class ArticulationData:
This quantity is the orientation of the actor frame of the root rigid body relative to the world.
"""
return self.root_com_state_w[:, 3:7]
@property
def root_com_vel_w(self) -> torch.Tensor:
"""Root center of mass velocity in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
velocity = self._root_physx_view.get_root_velocities()
return velocity
return self.root_com_state_w[:, 7:13]
return self.root_com_pose_w[:, 3:7]
@property
def root_com_lin_vel_w(self) -> torch.Tensor:
......@@ -750,11 +806,7 @@ class ArticulationData:
This quantity is the linear velocity of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
velocity = self._root_physx_view.get_root_velocities()
return velocity[:, 0:3]
return self.root_com_state_w[:, 7:10]
return self.root_com_vel_w[:, :3]
@property
def root_com_ang_vel_w(self) -> torch.Tensor:
......@@ -762,223 +814,205 @@ class ArticulationData:
This quantity is the angular velocity of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation (pose is of link)
velocity = self._root_physx_view.get_root_velocities()
return velocity[:, 3:6]
return self.root_com_state_w[:, 10:13]
return self.root_com_vel_w[:, 3:6]
@property
def root_com_lin_vel_b(self) -> torch.Tensor:
"""Root center of mass linear velocity in base frame. Shape is (num_instances, 3).
def body_link_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the linear velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
This quantity is the position of the articulation bodies' actor frame relative to the world.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_lin_vel_w)
return self.body_link_pose_w[..., :3]
@property
def root_com_ang_vel_b(self) -> torch.Tensor:
"""Root center of mass angular velocity in base world frame. Shape is (num_instances, 3).
def body_link_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).
This quantity is the angular velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
This quantity is the orientation of the articulation bodies' actor frame relative to the world.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_ang_vel_w)
return self.body_link_pose_w[..., 3:7]
@property
def body_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def body_link_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the position of the rigid bodies' actor frame relative to the world.
This quantity is the linear velocity of the articulation bodies' center of mass frame relative to the world.
"""
return self.body_state_w[..., :3]
return self.body_link_vel_w[..., :3]
@property
def body_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).
def body_link_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the orientation of the rigid bodies' actor frame relative to the world.
This quantity is the angular velocity of the articulation bodies' center of mass frame relative to the world.
"""
return self.body_state_w[..., 3:7]
return self.body_link_vel_w[..., 3:6]
@property
def body_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).
def body_com_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame relative
to the world.
This quantity is the position of the articulation bodies' actor frame.
"""
return self.body_state_w[..., 7:13]
return self.body_com_pose_w[..., :3]
@property
def body_lin_vel_w(self) -> torch.Tensor:
def body_com_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the principle axis of inertia of all bodies in simulation world frame.
Shape is (num_instances, num_bodies, 4).
This quantity is the orientation of the articulation bodies' actor frame.
"""
return self.body_com_pose_w[..., 3:7]
@property
def body_com_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
This quantity is the linear velocity of the articulation bodies' center of mass frame.
"""
return self.body_state_w[..., 7:10]
return self.body_com_vel_w[..., :3]
@property
def body_ang_vel_w(self) -> torch.Tensor:
def body_com_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
This quantity is the angular velocity of the articulation bodies' center of mass frame.
"""
return self.body_state_w[..., 10:13]
return self.body_com_vel_w[..., 3:6]
@property
def body_lin_acc_w(self) -> torch.Tensor:
def body_com_lin_acc_w(self) -> torch.Tensor:
"""Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the linear acceleration of the rigid bodies' center of mass frame relative to the world.
This quantity is the linear acceleration of the articulation bodies' center of mass frame.
"""
return self.body_acc_w[..., 0:3]
return self.body_com_acc_w[..., :3]
@property
def body_ang_acc_w(self) -> torch.Tensor:
def body_com_ang_acc_w(self) -> torch.Tensor:
"""Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the angular acceleration of the rigid bodies' center of mass frame relative to the world.
This quantity is the angular acceleration of the articulation bodies' center of mass frame.
"""
return self.body_acc_w[..., 3:6]
##
# Link body properties
##
return self.body_com_acc_w[..., 3:6]
@property
def body_link_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def body_com_pos_b(self) -> torch.Tensor:
"""Center of mass position of all of the bodies in their respective link frames.
Shape is (num_instances, num_bodies, 3).
This quantity is the position of the rigid bodies' actor frame relative to the world.
This quantity is the center of mass location relative to its body'slink frame.
"""
if self._body_link_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
pose = self._root_physx_view.get_link_transforms()
return pose[..., :3]
return self._body_link_state_w.data[..., :3]
return self.body_com_pose_b[..., :3]
@property
def body_link_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).
def body_com_quat_b(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the principle axis of inertia of all of the bodies in their
respective link frames. Shape is (num_instances, num_bodies, 4).
This quantity is the orientation of the rigid bodies' actor frame relative to the world.
This quantity is the orientation of the principles axes of inertia relative to its body's link frame.
"""
if self._body_link_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation
pose = self._root_physx_view.get_link_transforms().clone()
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
return pose[..., 3:7]
return self.body_link_state_w[..., 3:7]
return self.body_com_pose_b[..., 3:7]
##
# Backward compatibility.
##
@property
def body_link_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).
def root_pose_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_pose_w`."""
return self.root_link_pose_w
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame
relative to the world.
"""
return self.body_link_state_w[..., 7:13]
@property
def root_pos_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_pos_w`."""
return self.root_link_pos_w
@property
def body_link_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def root_quat_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_quat_w`."""
return self.root_link_quat_w
This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_link_state_w[..., 7:10]
@property
def root_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_vel_w`."""
return self.root_com_vel_w
@property
def body_link_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def root_lin_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_lin_vel_w`."""
return self.root_com_lin_vel_w
This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_link_state_w[..., 10:13]
@property
def root_ang_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_ang_vel_w`."""
return self.root_com_ang_vel_w
##
# Center of mass body properties
##
@property
def root_lin_vel_b(self) -> torch.Tensor:
"""Same as :attr:`root_com_lin_vel_b`."""
return self.root_com_lin_vel_b
@property
def body_com_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def root_ang_vel_b(self) -> torch.Tensor:
"""Same as :attr:`root_com_ang_vel_b`."""
return self.root_com_ang_vel_b
This quantity is the position of the rigid bodies' actor frame.
"""
return self.body_com_state_w[..., :3]
@property
def body_pose_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_pose_w`."""
return self.body_link_pose_w
@property
def body_com_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the prinicple axies of inertia of all bodies in simulation world frame.
def body_pos_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_pos_w`."""
return self.body_link_pos_w
Shape is (num_instances, num_bodies, 4). This quantity is the orientation of the rigid bodies' actor frame.
"""
return self.body_com_state_w[..., 3:7]
@property
def body_quat_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_quat_w`."""
return self.body_link_quat_w
@property
def body_com_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6).
def body_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_vel_w`."""
return self.body_com_vel_w
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
"""
if self._body_com_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation (velocity is of com)
velocity = self._root_physx_view.get_link_velocities()
return velocity
return self.body_com_state_w[..., 7:13]
@property
def body_lin_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_lin_vel_w`."""
return self.body_com_lin_vel_w
@property
def body_com_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def body_ang_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_ang_vel_w`."""
return self.body_com_ang_vel_w
This quantity is the linear velocity of the rigid bodies' center of mass frame.
"""
if self._body_com_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation (velocity is of com)
velocity = self._root_physx_view.get_link_velocities()
return velocity[..., 0:3]
return self.body_com_state_w[..., 7:10]
@property
def body_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_acc_w`."""
return self.body_com_acc_w
@property
def body_com_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
def body_lin_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_lin_acc_w`."""
return self.body_com_lin_acc_w
This quantity is the angular velocity of the rigid bodies' center of mass frame.
"""
if self._body_com_state_w.timestamp < self._sim_timestamp:
self._physics_sim_view.update_articulations_kinematic()
# read data from simulation (velocity is of com)
velocity = self._root_physx_view.get_link_velocities()
return velocity[..., 3:6]
return self.body_com_state_w[..., 10:13]
@property
def body_ang_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_ang_acc_w`."""
return self.body_com_ang_acc_w
@property
def com_pos_b(self) -> torch.Tensor:
"""Center of mass of all of the bodies in simulation world frame. Shape is (num_instances, num_bodies, 3).
This quantity is the center of mass location relative to its body frame.
"""
return self._root_physx_view.get_coms().to(self.device)[..., :3]
"""Same as :attr:`body_com_pos_b`."""
return self.body_com_pos_b
@property
def com_quat_b(self) -> torch.Tensor:
"""Orientation (w,x,y,z) of the principle axies of inertia of all of the bodies in simulation world frame. Shape is (num_instances, num_bodies, 4).
This quantity is the orientation of the principles axes of inertia relative to its body frame.
"""
quat = self._root_physx_view.get_coms().to(self.device)[..., 3:7]
return math_utils.convert_quat(quat, to="wxyz")
##
# Backward compatibility.
##
"""Same as :attr:`body_com_quat_b`."""
return self.body_com_quat_b
@property
def joint_limits(self) -> torch.Tensor:
......
......@@ -127,10 +127,7 @@ class DeformableObjectData:
Shape is (num_instances, max_sim_vertices_per_body, 6).
"""
if self._nodal_state_w.timestamp < self._sim_timestamp:
nodal_positions = self.nodal_pos_w
nodal_velocities = self.nodal_vel_w
# set the buffer data and timestamp
self._nodal_state_w.data = torch.cat((nodal_positions, nodal_velocities), dim=-1)
self._nodal_state_w.data = torch.cat((self.nodal_pos_w, self.nodal_vel_w), dim=-1)
self._nodal_state_w.timestamp = self._sim_timestamp
return self._nodal_state_w.data
......
......@@ -162,10 +162,8 @@ class RigidObject(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# 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)
self.write_root_link_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_com_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
def write_root_com_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass state over selected environment indices into the simulation.
......@@ -177,7 +175,6 @@ class RigidObject(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# set into simulation
self.write_root_com_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_com_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
......@@ -191,7 +188,6 @@ class RigidObject(AssetBase):
root_state: Root state in simulation frame. Shape is (len(env_ids), 13).
env_ids: Environment indices. If None, then all indices are used.
"""
# set into simulation
self.write_root_link_pose_to_sim(root_state[:, :7], env_ids=env_ids)
self.write_root_link_velocity_to_sim(root_state[:, 7:], env_ids=env_ids)
......@@ -201,22 +197,10 @@ class RigidObject(AssetBase):
The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
Args:
root_pose: Root poses in simulation frame. Shape is (len(env_ids), 7).
root_pose: Root link poses in simulation frame. Shape is (len(env_ids), 7).
env_ids: Environment indices. If None, then all indices are used.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, :7] = root_pose.clone()
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_state_w[:, :7].clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
# set into simulation
self.root_physx_view.set_transforms(root_poses_xyzw, indices=physx_env_ids)
self.write_root_link_pose_to_sim(root_pose, env_ids=env_ids)
def write_root_link_pose_to_sim(self, root_pose: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root link pose over selected environment indices into the simulation.
......@@ -224,7 +208,7 @@ class RigidObject(AssetBase):
The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
Args:
root_pose: Root poses in simulation frame. Shape is (len(env_ids), 7).
root_pose: Root link poses in simulation frame. Shape is (len(env_ids), 7).
env_ids: Environment indices. If None, then all indices are used.
"""
# resolve all indices
......@@ -232,13 +216,20 @@ class RigidObject(AssetBase):
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_link_state_w[env_ids, :7] = root_pose.clone()
self._data.root_state_w[env_ids, :7] = self._data.root_link_state_w[env_ids, :7]
self._data.root_link_pose_w[env_ids] = root_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_link_state_w.data is not None:
self._data.root_link_state_w[env_ids, :7] = self._data.root_link_pose_w[env_ids]
if self._data._root_state_w.data is not None:
self._data.root_state_w[env_ids, :7] = self._data.root_link_pose_w[env_ids]
# convert root quaternion from wxyz to xyzw
root_poses_xyzw = self._data.root_link_state_w[:, :7].clone()
root_poses_xyzw = self._data.root_link_pose_w.clone()
root_poses_xyzw[:, 3:] = math_utils.convert_quat(root_poses_xyzw[:, 3:], to="xyzw")
# set into simulation
self.root_physx_view.set_transforms(root_poses_xyzw, indices=physx_env_ids)
......@@ -258,18 +249,26 @@ class RigidObject(AssetBase):
else:
local_env_ids = env_ids
com_pos = self.data.com_pos_b[local_env_ids, 0, :]
com_quat = self.data.com_quat_b[local_env_ids, 0, :]
# set into internal buffers
self._data.root_com_pose_w[local_env_ids] = root_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_com_state_w.data is not None:
self._data.root_com_state_w[local_env_ids, :7] = self._data.root_com_pose_w[local_env_ids]
# get CoM pose in link frame
com_pos_b = self.data.body_com_pos_b[local_env_ids, 0, :]
com_quat_b = self.data.body_com_quat_b[local_env_ids, 0, :]
# transform input CoM pose to link frame
root_link_pos, root_link_quat = math_utils.combine_frame_transforms(
root_pose[..., :3],
root_pose[..., 3:7],
math_utils.quat_apply(math_utils.quat_inv(com_quat), -com_pos),
math_utils.quat_inv(com_quat),
math_utils.quat_apply(math_utils.quat_inv(com_quat_b), -com_pos_b),
math_utils.quat_inv(com_quat_b),
)
root_link_pose = torch.cat((root_link_pos, root_link_quat), dim=-1)
self.write_root_link_pose_to_sim(root_pose=root_link_pose, env_ids=env_ids)
# write transformed pose in link frame to sim
self.write_root_link_pose_to_sim(root_link_pose, env_ids=env_ids)
def write_root_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass velocity over selected environment indices into the simulation.
......@@ -281,17 +280,7 @@ class RigidObject(AssetBase):
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.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_state_w[env_ids, 7:] = root_velocity.clone()
self._data.body_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_velocities(self._data.root_state_w[:, 7:], indices=physx_env_ids)
self.write_root_com_velocity_to_sim(root_velocity=root_velocity, env_ids=env_ids)
def write_root_com_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root center of mass velocity over selected environment indices into the simulation.
......@@ -303,19 +292,25 @@ class RigidObject(AssetBase):
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.
"""
# resolve all indices
physx_env_ids = env_ids
if env_ids is None:
env_ids = slice(None)
physx_env_ids = self._ALL_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.root_com_state_w[env_ids, 7:] = root_velocity.clone()
self._data.root_state_w[env_ids, 7:] = self._data.root_com_state_w[env_ids, 7:]
self._data.body_acc_w[env_ids] = 0.0
self._data.root_com_vel_w[env_ids] = root_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_com_state_w.data is not None:
self._data.root_com_state_w[env_ids, 7:] = self._data.root_com_vel_w[env_ids]
if self._data._root_state_w.data is not None:
self._data.root_state_w[env_ids, 7:] = self._data.root_com_vel_w[env_ids]
# make the acceleration zero to prevent reporting old values
self._data.body_com_acc_w[env_ids] = 0.0
# set into simulation
self.root_physx_view.set_velocities(self._data.root_com_state_w[:, 7:], indices=physx_env_ids)
self.root_physx_view.set_velocities(self._data.root_com_vel_w, indices=physx_env_ids)
def write_root_link_velocity_to_sim(self, root_velocity: torch.Tensor, env_ids: Sequence[int] | None = None):
"""Set the root link velocity over selected environment indices into the simulation.
......@@ -333,15 +328,23 @@ class RigidObject(AssetBase):
else:
local_env_ids = env_ids
# set into internal buffers
self._data.root_link_vel_w[local_env_ids] = root_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._root_link_state_w.data is not None:
self._data.root_link_state_w[local_env_ids, 7:] = self._data.root_link_vel_w[local_env_ids]
# get CoM pose in link frame
quat = self.data.root_link_quat_w[local_env_ids]
com_pos_b = self.data.body_com_pos_b[local_env_ids, 0, :]
# transform input velocity to center of mass frame
root_com_velocity = root_velocity.clone()
quat = self.data.root_link_state_w[local_env_ids, 3:7]
com_pos_b = self.data.com_pos_b[local_env_ids, 0, :]
# transform given velocity to center of mass
root_com_velocity[:, :3] += torch.linalg.cross(
root_com_velocity[:, 3:], math_utils.quat_apply(quat, com_pos_b), dim=-1
)
# write center of mass velocity to sim
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity, env_ids=env_ids)
# write transformed velocity in CoM frame to sim
self.write_root_com_velocity_to_sim(root_com_velocity, env_ids=env_ids)
"""
Operations - Setters.
......
......@@ -68,10 +68,19 @@ class RigidObjectData:
self.FORWARD_VEC_B = torch.tensor((1.0, 0.0, 0.0), device=self.device).repeat(self._root_physx_view.count, 1)
# Initialize the lazy buffers.
# -- link frame w.r.t. world frame
self._root_link_pose_w = TimestampedBuffer()
self._root_link_vel_w = TimestampedBuffer()
# -- com frame w.r.t. link frame
self._body_com_pose_b = TimestampedBuffer()
# -- com frame w.r.t. world frame
self._root_com_pose_w = TimestampedBuffer()
self._root_com_vel_w = TimestampedBuffer()
self._body_com_acc_w = TimestampedBuffer()
# -- combined state (these are cached as they concatenate)
self._root_state_w = TimestampedBuffer()
self._root_link_state_w = TimestampedBuffer()
self._root_com_state_w = TimestampedBuffer()
self._body_acc_w = TimestampedBuffer()
def update(self, dt: float):
"""Updates the data for the rigid object.
......@@ -111,192 +120,279 @@ class RigidObjectData:
"""
##
# Properties.
# Root state properties.
##
@property
def root_state_w(self):
"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13).
def root_link_pose_w(self) -> torch.Tensor:
"""Root link pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 7).
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.
This quantity is the pose of the actor frame of the root rigid body relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._root_state_w.timestamp < self._sim_timestamp:
if self._root_link_pose_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_velocities()
# set the buffer data and timestamp
self._root_state_w.data = torch.cat((pose, velocity), dim=-1)
self._root_link_pose_w.data = pose
self._root_link_pose_w.timestamp = self._sim_timestamp
return self._root_link_pose_w.data
@property
def root_link_vel_w(self) -> torch.Tensor:
"""Root link velocity ``[lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the actor frame of the root
rigid body relative to the world.
"""
if self._root_link_vel_w.timestamp < self._sim_timestamp:
# read the CoM velocity
vel = self.root_com_vel_w.clone()
# adjust linear velocity to link from center of mass
vel[:, :3] += torch.linalg.cross(
vel[:, 3:], math_utils.quat_apply(self.root_link_quat_w, -self.body_com_pos_b[:, 0]), dim=-1
)
# set the buffer data and timestamp
self._root_link_vel_w.data = vel
self._root_link_vel_w.timestamp = self._sim_timestamp
return self._root_link_vel_w.data
@property
def root_com_pose_w(self) -> torch.Tensor:
"""Root center of mass pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 7).
This quantity is the pose of the center of mass frame of the root rigid body relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
if self._root_com_pose_w.timestamp < self._sim_timestamp:
# apply local transform to center of mass frame
pos, quat = math_utils.combine_frame_transforms(
self.root_link_pos_w, self.root_link_quat_w, self.body_com_pos_b[:, 0], self.body_com_quat_b[:, 0]
)
# set the buffer data and timestamp
self._root_com_pose_w.data = torch.cat((pos, quat), dim=-1)
self._root_com_pose_w.timestamp = self._sim_timestamp
return self._root_com_pose_w.data
@property
def root_com_vel_w(self) -> torch.Tensor:
"""Root center of mass velocity ``[lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the root rigid body's center of mass frame
relative to the world.
"""
if self._root_com_vel_w.timestamp < self._sim_timestamp:
self._root_com_vel_w.data = self._root_physx_view.get_velocities()
self._root_com_vel_w.timestamp = self._sim_timestamp
return self._root_com_vel_w.data
@property
def root_state_w(self) -> torch.Tensor:
"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13).
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 self._root_state_w.timestamp < self._sim_timestamp:
self._root_state_w.data = torch.cat((self.root_link_pose_w, self.root_com_vel_w), dim=-1)
self._root_state_w.timestamp = self._sim_timestamp
return self._root_state_w.data
@property
def root_link_state_w(self):
def root_link_state_w(self) -> torch.Tensor:
"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13).
The position, quaternion, and linear/angular velocity are of the rigid body root frame relative to the
world.
world. The orientation is provided in (w, x, y, z) format.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_velocities().clone()
# adjust linear velocity to link from center of mass
velocity[:, :3] += torch.linalg.cross(
velocity[:, 3:], math_utils.quat_apply(pose[:, 3:7], -self.com_pos_b[:, 0, :]), dim=-1
)
# set the buffer data and timestamp
self._root_link_state_w.data = torch.cat((pose, velocity), dim=-1)
self._root_link_state_w.data = torch.cat((self.root_link_pose_w, self.root_link_vel_w), dim=-1)
self._root_link_state_w.timestamp = self._sim_timestamp
return self._root_link_state_w.data
@property
def root_com_state_w(self):
"""Root center of mass state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13).
def root_com_state_w(self) -> torch.Tensor:
"""Root center of mass state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, 13).
The position, quaternion, and linear/angular velocity are of the rigid body's center of mass frame
relative to the world. Center of mass frame is the orientation principle axes of inertia.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation (pose is of link)
pose = self._root_physx_view.get_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
velocity = self._root_physx_view.get_velocities()
# adjust pose to center of mass
pos, quat = math_utils.combine_frame_transforms(
pose[:, :3], pose[:, 3:7], self.com_pos_b[:, 0, :], self.com_quat_b[:, 0, :]
)
pose = torch.cat((pos, quat), dim=-1)
# set the buffer data and timestamp
self._root_com_state_w.data = torch.cat((pos, quat, velocity), dim=-1)
self._root_com_state_w.data = torch.cat((self.root_com_pose_w, self.root_com_vel_w), dim=-1)
self._root_com_state_w.timestamp = self._sim_timestamp
return self._root_com_state_w.data
##
# Body state properties.
##
@property
def body_link_pose_w(self) -> torch.Tensor:
"""Body link pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 1, 7).
This quantity is the pose of the actor frame of the rigid body relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
return self.root_link_pose_w.view(-1, 1, 7)
@property
def body_link_vel_w(self) -> torch.Tensor:
"""Body link velocity ``[lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 1, 6).
This quantity contains the linear and angular velocities of the actor frame of the root
rigid body relative to the world.
"""
return self.root_link_vel_w.view(-1, 1, 6)
@property
def body_state_w(self):
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is (num_instances, 1, 13).
def body_com_pose_w(self) -> torch.Tensor:
"""Body center of mass pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, 1, 7).
This quantity is the pose of the center of mass frame of the rigid body relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
return self.root_com_pose_w.view(-1, 1, 7)
@property
def body_com_vel_w(self) -> torch.Tensor:
"""Body center of mass velocity ``[lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, 1, 6).
This quantity contains the linear and angular velocities of the root rigid body's center of mass frame
relative to the world.
"""
return self.root_com_vel_w.view(-1, 1, 6)
@property
def body_state_w(self) -> torch.Tensor:
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame.
Shape is (num_instances, 1, 13).
The position and orientation are of the rigid bodies' actor frame. Meanwhile, the linear and angular
velocities are of the rigid bodies' center of mass frame.
"""
return self.root_state_w.view(-1, 1, 13)
@property
def body_link_state_w(self):
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame.
def body_link_state_w(self) -> torch.Tensor:
"""State of all bodies ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, 1, 13).
The position, quaternion, and linear/angular velocity are of the body's link frame relative to the world.
The orientation is provided in (w, x, y, z) format.
"""
return self.root_link_state_w.view(-1, 1, 13)
@property
def body_com_state_w(self):
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame.
def body_com_state_w(self) -> torch.Tensor:
"""State of all bodies ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, num_bodies, 13).
The position, quaternion, and linear/angular velocity are of the body's center of mass frame relative to the
world. Center of mass frame is assumed to be the same orientation as the link rather than the orientation of the
principle inertia.
principle inertia. The orientation is provided in (w, x, y, z) format.
"""
return self.root_com_state_w.view(-1, 1, 13)
@property
def body_acc_w(self):
"""Acceleration of all bodies. Shape is (num_instances, 1, 6).
def body_com_acc_w(self) -> torch.Tensor:
"""Acceleration of all bodies ``[lin_acc, ang_acc]`` in the simulation world frame.
Shape is (num_instances, 1, 6).
This quantity is the acceleration of the rigid bodies' center of mass frame.
This quantity is the acceleration of the rigid bodies' center of mass frame relative to the world.
"""
if self._body_acc_w.timestamp < self._sim_timestamp:
# note: we use finite differencing to compute acceleration
self._body_acc_w.data = self._root_physx_view.get_accelerations().unsqueeze(1)
self._body_acc_w.timestamp = self._sim_timestamp
return self._body_acc_w.data
if self._body_com_acc_w.timestamp < self._sim_timestamp:
self._body_com_acc_w.data = self._root_physx_view.get_accelerations().unsqueeze(1)
self._body_com_acc_w.timestamp = self._sim_timestamp
@property
def projected_gravity_b(self):
"""Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.GRAVITY_VEC_W)
return self._body_com_acc_w.data
@property
def heading_w(self):
"""Yaw heading of the base frame (in radians). Shape is (num_instances,).
def body_com_pose_b(self) -> torch.Tensor:
"""Center of mass pose ``[pos, quat]`` of all bodies in their respective body's link frames.
Shape is (num_instances, 1, 7).
Note:
This quantity is computed by assuming that the forward-direction of the base
frame is along x-direction, i.e. :math:`(1, 0, 0)`.
This quantity is the pose of the center of mass frame of the rigid body relative to the body's link frame.
The orientation is provided in (w, x, y, z) format.
"""
forward_w = math_utils.quat_apply(self.root_link_quat_w, self.FORWARD_VEC_B)
return torch.atan2(forward_w[:, 1], forward_w[:, 0])
if self._body_com_pose_b.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_coms().to(self.device)
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
# set the buffer data and timestamp
self._body_com_pose_b.data = pose.view(-1, 1, 7)
self._body_com_pose_b.timestamp = self._sim_timestamp
return self._body_com_pose_b.data
##
# Derived properties.
# Derived Properties.
##
@property
def root_pos_w(self) -> torch.Tensor:
"""Root position in simulation world frame. Shape is (num_instances, 3).
This quantity is the position of the actor frame of the root rigid body.
"""
return self.root_state_w[:, :3]
@property
def root_quat_w(self) -> torch.Tensor:
"""Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4).
This quantity is the orientation of the actor frame of the root rigid body.
"""
return self.root_state_w[:, 3:7]
def projected_gravity_b(self) -> torch.Tensor:
"""Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.GRAVITY_VEC_W)
@property
def root_vel_w(self) -> torch.Tensor:
"""Root velocity in simulation world frame. Shape is (num_instances, 6).
def heading_w(self) -> torch.Tensor:
"""Yaw heading of the base frame (in radians). Shape is (num_instances,).
This quantity contains the linear and angular velocities of the root rigid body's center of mass frame.
Note:
This quantity is computed by assuming that the forward-direction of the base
frame is along x-direction, i.e. :math:`(1, 0, 0)`.
"""
return self.root_state_w[:, 7:13]
forward_w = math_utils.quat_apply(self.root_link_quat_w, self.FORWARD_VEC_B)
return torch.atan2(forward_w[:, 1], forward_w[:, 0])
@property
def root_lin_vel_w(self) -> torch.Tensor:
"""Root linear velocity in simulation world frame. Shape is (num_instances, 3).
def root_link_lin_vel_b(self) -> torch.Tensor:
"""Root link linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the root rigid body's center of mass frame relative to the world.
This quantity is the linear velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return self.root_state_w[:, 7:10]
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_lin_vel_w)
@property
def root_ang_vel_w(self) -> torch.Tensor:
"""Root angular velocity in simulation world frame. Shape is (num_instances, 3).
def root_link_ang_vel_b(self) -> torch.Tensor:
"""Root link angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the root rigid body's center of mass frame.
This quantity is the angular velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return self.root_state_w[:, 10:13]
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_ang_vel_w)
@property
def root_lin_vel_b(self) -> torch.Tensor:
"""Root linear velocity in base frame. Shape is (num_instances, 3).
def root_com_lin_vel_b(self) -> torch.Tensor:
"""Root center of mass linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_lin_vel_w)
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_lin_vel_w)
@property
def root_ang_vel_b(self) -> torch.Tensor:
"""Root angular velocity in base world frame. Shape is (num_instances, 3).
def root_com_ang_vel_b(self) -> torch.Tensor:
"""Root center of mass angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_ang_vel_w)
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_ang_vel_w)
##
# Sliced properties.
##
@property
def root_link_pos_w(self) -> torch.Tensor:
......@@ -304,11 +400,7 @@ class RigidObjectData:
This quantity is the position of the actor frame of the root rigid body relative to the world.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_transforms()
return pose[:, :3]
return self.root_link_state_w[:, :3]
return self.root_link_pose_w[:, :3]
@property
def root_link_quat_w(self) -> torch.Tensor:
......@@ -316,21 +408,7 @@ class RigidObjectData:
This quantity is the orientation of the actor frame of the root rigid body.
"""
if self._root_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._root_physx_view.get_transforms().clone()
pose[:, 3:7] = math_utils.convert_quat(pose[:, 3:7], to="wxyz")
return pose[:, 3:7]
return self.root_link_state_w[:, 3:7]
@property
def root_link_vel_w(self) -> torch.Tensor:
"""Root link velocity in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the actor frame of the root
rigid body relative to the world.
"""
return self.root_link_state_w[:, 7:13]
return self.root_link_pose_w[:, 3:7]
@property
def root_link_lin_vel_w(self) -> torch.Tensor:
......@@ -338,7 +416,7 @@ class RigidObjectData:
This quantity is the linear velocity of the root rigid body's actor frame relative to the world.
"""
return self.root_link_state_w[:, 7:10]
return self.root_link_vel_w[:, :3]
@property
def root_link_ang_vel_w(self) -> torch.Tensor:
......@@ -346,25 +424,7 @@ class RigidObjectData:
This quantity is the angular velocity of the actor frame of the root rigid body relative to the world.
"""
return self.root_link_state_w[:, 10:13]
@property
def root_link_lin_vel_b(self) -> torch.Tensor:
"""Root link linear velocity in base frame. Shape is (num_instances, 3).
This quantity is the linear velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_lin_vel_w)
@property
def root_link_ang_vel_b(self) -> torch.Tensor:
"""Root link angular velocity in base world frame. Shape is (num_instances, 3).
This quantity is the angular velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_link_ang_vel_w)
return self.root_link_vel_w[:, 3:6]
@property
def root_com_pos_w(self) -> torch.Tensor:
......@@ -372,7 +432,7 @@ class RigidObjectData:
This quantity is the position of the actor frame of the root rigid body relative to the world.
"""
return self.root_com_state_w[:, :3]
return self.root_com_pose_w[:, :3]
@property
def root_com_quat_w(self) -> torch.Tensor:
......@@ -380,19 +440,7 @@ class RigidObjectData:
This quantity is the orientation of the actor frame of the root rigid body relative to the world.
"""
return self.root_com_state_w[:, 3:7]
@property
def root_com_vel_w(self) -> torch.Tensor:
"""Root center of mass velocity in simulation world frame. Shape is (num_instances, 6).
This quantity contains the linear and angular velocities of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._root_physx_view.get_velocities()
return velocity
return self.root_com_state_w[:, 7:13]
return self.root_com_pose_w[:, 3:7]
@property
def root_com_lin_vel_w(self) -> torch.Tensor:
......@@ -400,11 +448,7 @@ class RigidObjectData:
This quantity is the linear velocity of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._root_physx_view.get_velocities()
return velocity[:, 0:3]
return self.root_com_state_w[:, 7:10]
return self.root_com_vel_w[:, :3]
@property
def root_com_ang_vel_w(self) -> torch.Tensor:
......@@ -412,188 +456,201 @@ class RigidObjectData:
This quantity is the angular velocity of the root rigid body's center of mass frame relative to the world.
"""
if self._root_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._root_physx_view.get_velocities()
return velocity[:, 3:6]
return self.root_com_state_w[:, 10:13]
return self.root_com_vel_w[:, 3:6]
@property
def root_com_lin_vel_b(self) -> torch.Tensor:
"""Root center of mass linear velocity in base frame. Shape is (num_instances, 3).
def body_link_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the linear velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
This quantity is the position of the rigid bodies' actor frame relative to the world.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_lin_vel_w)
return self.body_link_pose_w[..., :3]
@property
def root_com_ang_vel_b(self) -> torch.Tensor:
"""Root center of mass angular velocity in base world frame. Shape is (num_instances, 3).
def body_link_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, 1, 4).
This quantity is the angular velocity of the root rigid body's center of mass frame with respect to the
rigid body's actor frame.
This quantity is the orientation of the rigid bodies' actor frame relative to the world.
"""
return math_utils.quat_apply_inverse(self.root_link_quat_w, self.root_com_ang_vel_w)
return self.body_link_pose_w[..., 3:7]
@property
def body_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def body_link_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the position of the rigid bodies' actor frame.
This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_state_w[..., :3]
return self.body_link_vel_w[..., :3]
@property
def body_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, 1, 4).
def body_link_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the orientation of the rigid bodies' actor frame.
This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_state_w[..., 3:7]
return self.body_link_vel_w[..., 3:6]
@property
def body_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6).
def body_com_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
This quantity is the position of the rigid bodies' actor frame.
"""
return self.body_state_w[..., 7:13]
return self.body_com_pose_w[..., :3]
@property
def body_lin_vel_w(self) -> torch.Tensor:
def body_com_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the principle axis of inertia of all bodies in simulation world frame.
Shape is (num_instances, 1, 4). This quantity is the orientation of the rigid bodies' actor frame.
"""
return self.body_com_pose_w[..., 3:7]
@property
def body_com_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the linear velocity of the rigid bodies' center of mass frame.
"""
return self.body_state_w[..., 7:10]
return self.body_com_vel_w[..., :3]
@property
def body_ang_vel_w(self) -> torch.Tensor:
def body_com_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the angular velocity of the rigid bodies' center of mass frame.
"""
return self.body_state_w[..., 10:13]
return self.body_com_vel_w[..., 3:6]
@property
def body_lin_acc_w(self) -> torch.Tensor:
def body_com_lin_acc_w(self) -> torch.Tensor:
"""Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the linear acceleration of the rigid bodies' center of mass frame.
"""
return self.body_acc_w[..., 0:3]
return self.body_com_acc_w[..., :3]
@property
def body_ang_acc_w(self) -> torch.Tensor:
def body_com_ang_acc_w(self) -> torch.Tensor:
"""Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the angular acceleration of the rigid bodies' center of mass frame.
"""
return self.body_acc_w[..., 3:6]
#
# Link body properties
#
return self.body_com_acc_w[..., 3:6]
@property
def body_link_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def body_com_pos_b(self) -> torch.Tensor:
"""Center of mass position of all of the bodies in their respective link frames.
Shape is (num_instances, 1, 3).
This quantity is the position of the rigid bodies' actor frame relative to the world.
This quantity is the center of mass location relative to its body'slink frame.
"""
return self.body_link_state_w[..., :3]
return self.body_com_pose_b[..., :3]
@property
def body_link_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, 1, 4).
def body_com_quat_b(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the principle axis of inertia of all of the bodies in their
respective link frames. Shape is (num_instances, 1, 4).
This quantity is the orientation of the rigid bodies' actor frame relative to the world.
This quantity is the orientation of the principles axes of inertia relative to its body's link frame.
"""
return self.body_link_state_w[..., 3:7]
return self.body_com_pose_b[..., 3:7]
##
# Properties for backwards compatibility.
##
@property
def body_link_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6).
def root_pose_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_pose_w`."""
return self.root_link_pose_w
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame
relative to the world.
"""
return self.body_link_state_w[..., 7:13]
@property
def root_pos_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_pos_w`."""
return self.root_link_pos_w
@property
def body_link_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def root_quat_w(self) -> torch.Tensor:
"""Same as :attr:`root_link_quat_w`."""
return self.root_link_quat_w
This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_link_state_w[..., 7:10]
@property
def root_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_vel_w`."""
return self.root_com_vel_w
@property
def body_link_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def root_lin_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_lin_vel_w`."""
return self.root_com_lin_vel_w
This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
"""
return self.body_link_state_w[..., 10:13]
@property
def root_ang_vel_w(self) -> torch.Tensor:
"""Same as :attr:`root_com_ang_vel_w`."""
return self.root_com_ang_vel_w
#
# Center of mass body properties
#
@property
def root_lin_vel_b(self) -> torch.Tensor:
"""Same as :attr:`root_com_lin_vel_b`."""
return self.root_com_lin_vel_b
@property
def body_com_pos_w(self) -> torch.Tensor:
"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def root_ang_vel_b(self) -> torch.Tensor:
"""Same as :attr:`root_com_ang_vel_b`."""
return self.root_com_ang_vel_b
This quantity is the position of the rigid bodies' actor frame.
"""
return self.body_com_state_w[..., :3]
@property
def body_pose_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_pose_w`."""
return self.body_link_pose_w
@property
def body_com_quat_w(self) -> torch.Tensor:
"""Orientation (w, x, y, z) of the prinicple axies of inertia of all bodies in simulation world frame.
def body_pos_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_pos_w`."""
return self.body_link_pos_w
Shape is (num_instances, 1, 4). This quantity is the orientation of the rigid bodies' actor frame.
"""
return self.body_com_state_w[..., 3:7]
@property
def body_quat_w(self) -> torch.Tensor:
"""Same as :attr:`body_link_quat_w`."""
return self.body_link_quat_w
@property
def body_com_vel_w(self) -> torch.Tensor:
"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6).
def body_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_vel_w`."""
return self.body_com_vel_w
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
"""
return self.body_com_state_w[..., 7:13]
@property
def body_lin_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_lin_vel_w`."""
return self.body_com_lin_vel_w
@property
def body_com_lin_vel_w(self) -> torch.Tensor:
"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def body_ang_vel_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_ang_vel_w`."""
return self.body_com_ang_vel_w
This quantity is the linear velocity of the rigid bodies' center of mass frame.
"""
return self.body_com_state_w[..., 7:10]
@property
def body_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_acc_w`."""
return self.body_com_acc_w
@property
def body_com_ang_vel_w(self) -> torch.Tensor:
"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3).
def body_lin_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_lin_acc_w`."""
return self.body_com_lin_acc_w
This quantity is the angular velocity of the rigid bodies' center of mass frame.
"""
return self.body_com_state_w[..., 10:13]
@property
def body_ang_acc_w(self) -> torch.Tensor:
"""Same as :attr:`body_com_ang_acc_w`."""
return self.body_com_ang_acc_w
@property
def com_pos_b(self) -> torch.Tensor:
"""Center of mass of all of the bodies in simulation world frame. Shape is (num_instances, 1, 3).
This quantity is the center of mass location relative to its body frame.
"""
return self._root_physx_view.get_coms().to(self.device)[..., :3].view(-1, 1, 3)
"""Same as :attr:`body_com_pos_b`."""
return self.body_com_pos_b
@property
def com_quat_b(self) -> torch.Tensor:
"""Orientation (w,x,y,z) of the prinicple axies of inertia of all of the bodies in simulation world frame. Shape is (num_instances, 1, 4).
This quantity is the orientation of the principles axes of inertia relative to its body frame.
"""
quat = self._root_physx_view.get_coms().to(self.device)[..., 3:7]
return math_utils.convert_quat(quat, to="wxyz").view(-1, 1, 4)
"""Same as :attr:`body_com_quat_b`."""
return self.body_com_quat_b
......@@ -233,10 +233,8 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# set into simulation
self.write_object_pose_to_sim(object_state[..., :7], env_ids=env_ids, object_ids=object_ids)
self.write_object_velocity_to_sim(object_state[..., 7:], env_ids=env_ids, object_ids=object_ids)
self.write_object_link_pose_to_sim(object_state[..., :7], env_ids=env_ids, object_ids=object_ids)
self.write_object_com_velocity_to_sim(object_state[..., 7:], env_ids=env_ids, object_ids=object_ids)
def write_object_com_state_to_sim(
self,
......@@ -245,6 +243,7 @@ class RigidObjectCollection(AssetBase):
object_ids: slice | torch.Tensor | None = None,
):
"""Set the object center of mass state over selected environment indices into the simulation.
The object state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear
and angular velocity. All the quantities are in the simulation frame.
......@@ -253,7 +252,6 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# set into simulation
self.write_object_com_pose_to_sim(object_state[..., :7], env_ids=env_ids, object_ids=object_ids)
self.write_object_com_velocity_to_sim(object_state[..., 7:], env_ids=env_ids, object_ids=object_ids)
......@@ -264,6 +262,7 @@ class RigidObjectCollection(AssetBase):
object_ids: slice | torch.Tensor | None = None,
):
"""Set the object link state over selected environment indices into the simulation.
The object state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear
and angular velocity. All the quantities are in the simulation frame.
......@@ -272,7 +271,6 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# set into simulation
self.write_object_link_pose_to_sim(object_state[..., :7], env_ids=env_ids, object_ids=object_ids)
self.write_object_link_velocity_to_sim(object_state[..., 7:], env_ids=env_ids, object_ids=object_ids)
......@@ -291,22 +289,7 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# resolve all indices
# -- env_ids
if env_ids is None:
env_ids = self._ALL_ENV_INDICES
# -- object_ids
if object_ids is None:
object_ids = self._ALL_OBJ_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.object_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
# convert the quaternion from wxyz to xyzw
poses_xyzw = self._data.object_state_w[..., :7].clone()
poses_xyzw[..., 3:] = math_utils.convert_quat(poses_xyzw[..., 3:], to="xyzw")
# set into simulation
view_ids = self._env_obj_ids_to_view_ids(env_ids, object_ids)
self.root_physx_view.set_transforms(self.reshape_data_to_view(poses_xyzw), indices=view_ids)
self.write_object_link_pose_to_sim(object_pose, env_ids=env_ids, object_ids=object_ids)
def write_object_link_pose_to_sim(
self,
......@@ -323,7 +306,6 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# resolve all indices
# -- env_ids
if env_ids is None:
......@@ -331,13 +313,20 @@ class RigidObjectCollection(AssetBase):
# -- object_ids
if object_ids is None:
object_ids = self._ALL_OBJ_INDICES
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.object_link_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
self._data.object_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
self._data.object_link_pose_w[env_ids[:, None], object_ids] = object_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._object_link_state_w.data is not None:
self._data.object_link_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
if self._data._object_state_w.data is not None:
self._data.object_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
# convert the quaternion from wxyz to xyzw
poses_xyzw = self._data.object_link_state_w[..., :7].clone()
poses_xyzw = self._data.object_link_pose_w.clone()
poses_xyzw[..., 3:] = math_utils.convert_quat(poses_xyzw[..., 3:], to="xyzw")
# set into simulation
view_ids = self._env_obj_ids_to_view_ids(env_ids, object_ids)
self.root_physx_view.set_transforms(self.reshape_data_to_view(poses_xyzw), indices=view_ids)
......@@ -349,36 +338,43 @@ class RigidObjectCollection(AssetBase):
object_ids: slice | torch.Tensor | None = None,
):
"""Set the object center of mass pose over selected environment indices into the simulation.
The object pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
The orientation is the orientation of the principle axes of inertia.
Args:
object_pose: Object poses in simulation frame. Shape is (len(env_ids), len(object_ids), 7).
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# resolve all indices
# -- env_ids
if env_ids is None:
local_env_ids = slice(env_ids)
else:
local_env_ids = env_ids
env_ids = self._ALL_ENV_INDICES
# -- object_ids
if object_ids is None:
local_object_ids = slice(object_ids)
else:
local_object_ids = object_ids
com_pos = self.data.com_pos_b[local_env_ids][:, local_object_ids, :]
com_quat = self.data.com_quat_b[local_env_ids][:, local_object_ids, :]
object_ids = self._ALL_OBJ_INDICES
# set into internal buffers
self._data.object_com_pose_w[env_ids[:, None], object_ids] = object_pose.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._object_com_state_w.data is not None:
self._data.object_com_state_w[env_ids[:, None], object_ids, :7] = object_pose.clone()
# get CoM pose in link frame
com_pos_b = self.data.object_com_pos_b[env_ids[:, None], object_ids]
com_quat_b = self.data.object_com_quat_b[env_ids[:, None], object_ids]
# transform input CoM pose to link frame
object_link_pos, object_link_quat = math_utils.combine_frame_transforms(
object_pose[..., :3],
object_pose[..., 3:7],
math_utils.quat_apply(math_utils.quat_inv(com_quat), -com_pos),
math_utils.quat_inv(com_quat),
math_utils.quat_apply(math_utils.quat_inv(com_quat_b), -com_pos_b),
math_utils.quat_inv(com_quat_b),
)
# write transformed pose in link frame to sim
object_link_pose = torch.cat((object_link_pos, object_link_quat), dim=-1)
self.write_object_link_pose_to_sim(object_pose=object_link_pose, env_ids=env_ids, object_ids=object_ids)
self.write_object_link_pose_to_sim(object_link_pose, env_ids=env_ids, object_ids=object_ids)
def write_object_velocity_to_sim(
self,
......@@ -393,22 +389,7 @@ class RigidObjectCollection(AssetBase):
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# resolve all indices
# -- env_ids
if env_ids is None:
env_ids = self._ALL_ENV_INDICES
# -- object_ids
if object_ids is None:
object_ids = self._ALL_OBJ_INDICES
self._data.object_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
self._data.object_acc_w[env_ids[:, None], object_ids] = 0.0
# set into simulation
view_ids = self._env_obj_ids_to_view_ids(env_ids, object_ids)
self.root_physx_view.set_velocities(
self.reshape_data_to_view(self._data.object_state_w[..., 7:]), indices=view_ids
)
self.write_object_com_velocity_to_sim(object_velocity, env_ids=env_ids, object_ids=object_ids)
def write_object_com_velocity_to_sim(
self,
......@@ -431,15 +412,20 @@ class RigidObjectCollection(AssetBase):
if object_ids is None:
object_ids = self._ALL_OBJ_INDICES
self._data.object_com_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
self._data.object_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
self._data.object_acc_w[env_ids[:, None], object_ids] = 0.0
# note: we need to do this here since tensors are not set into simulation until step.
# set into internal buffers
self._data.object_com_vel_w[env_ids[:, None], object_ids] = object_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._object_com_state_w.data is not None:
self._data.object_com_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
if self._data._object_state_w.data is not None:
self._data.object_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
# make the acceleration zero to prevent reporting old values
self._data.object_com_acc_w[env_ids[:, None], object_ids] = 0.0
# set into simulation
view_ids = self._env_obj_ids_to_view_ids(env_ids, object_ids)
self.root_physx_view.set_velocities(
self.reshape_data_to_view(self._data.object_com_state_w[..., 7:]), indices=view_ids
)
self.root_physx_view.set_velocities(self.reshape_data_to_view(self._data.object_com_vel_w), indices=view_ids)
def write_object_link_velocity_to_sim(
self,
......@@ -448,34 +434,40 @@ class RigidObjectCollection(AssetBase):
object_ids: slice | torch.Tensor | None = None,
):
"""Set the object link velocity over selected environment indices into the simulation.
The velocity comprises linear velocity (x, y, z) and angular velocity (x, y, z) in that order.
NOTE: This sets the velocity of the object's frame rather than the objects center of mass.
Args:
object_velocity: Object velocities in simulation frame. Shape is (len(env_ids), len(object_ids), 6).
env_ids: Environment indices. If None, then all indices are used.
object_ids: Object indices. If None, then all indices are used.
"""
# resolve all indices
# -- env_ids
if env_ids is None:
local_env_ids = slice(env_ids)
else:
local_env_ids = env_ids
env_ids = self._ALL_ENV_INDICES
# -- object_ids
if object_ids is None:
local_object_ids = slice(object_ids)
else:
local_object_ids = object_ids
object_ids = self._ALL_OBJ_INDICES
# set into internal buffers
self._data.object_link_vel_w[env_ids[:, None], object_ids] = object_velocity.clone()
# update these buffers only if the user is using them. Otherwise this adds to overhead.
if self._data._object_link_state_w.data is not None:
self._data.object_link_state_w[env_ids[:, None], object_ids, 7:] = object_velocity.clone()
# get CoM pose in link frame
quat = self.data.object_link_quat_w[env_ids[:, None], object_ids]
com_pos_b = self.data.object_com_pos_b[env_ids[:, None], object_ids]
# transform input velocity to center of mass frame
object_com_velocity = object_velocity.clone()
quat = self.data.object_link_state_w[local_env_ids][:, local_object_ids, 3:7]
com_pos_b = self.data.com_pos_b[local_env_ids][:, local_object_ids, :]
# transform given velocity to center of mass
object_com_velocity[..., :3] += torch.linalg.cross(
object_com_velocity[..., 3:], math_utils.quat_apply(quat, com_pos_b), dim=-1
)
# write center of mass velocity to sim
self.write_object_com_velocity_to_sim(
object_velocity=object_com_velocity, env_ids=env_ids, object_ids=object_ids
)
self.write_object_com_velocity_to_sim(object_com_velocity, env_ids=env_ids, object_ids=object_ids)
"""
Operations - Setters.
......@@ -532,6 +524,33 @@ class RigidObjectCollection(AssetBase):
self._external_force_b[env_ids[:, None], object_ids] = forces
self._external_torque_b[env_ids[:, None], object_ids] = torques
"""
Helper functions.
"""
def reshape_view_to_data(self, data: torch.Tensor) -> torch.Tensor:
"""Reshapes and arranges the data coming from the :attr:`root_physx_view` to
(num_instances, num_objects, data_dim).
Args:
data: The data coming from the :attr:`root_physx_view`. Shape is (num_instances * num_objects, data_dim).
Returns:
The reshaped data. Shape is (num_instances, num_objects, data_dim).
"""
return torch.einsum("ijk -> jik", data.reshape(self.num_objects, self.num_instances, -1))
def reshape_data_to_view(self, data: torch.Tensor) -> torch.Tensor:
"""Reshapes and arranges the data to the be consistent with data from the :attr:`root_physx_view`.
Args:
data: The data to be reshaped. Shape is (num_instances, num_objects, data_dim).
Returns:
The reshaped data. Shape is (num_instances * num_objects, data_dim).
"""
return torch.einsum("ijk -> jik", data).reshape(self.num_objects * self.num_instances, *data.shape[2:])
"""
Internal helper.
"""
......@@ -643,28 +662,6 @@ class RigidObjectCollection(AssetBase):
default_object_states = torch.cat(default_object_states, dim=1)
self._data.default_object_state = default_object_states
def reshape_view_to_data(self, data: torch.Tensor) -> torch.Tensor:
"""Reshapes and arranges the data coming from the :attr:`root_physx_view` to (num_instances, num_objects, data_size).
Args:
data: The data coming from the :attr:`root_physx_view`. Shape is (num_instances*num_objects, data_size).
Returns:
The reshaped data. Shape is (num_instances, num_objects, data_size).
"""
return torch.einsum("ijk -> jik", data.reshape(self.num_objects, self.num_instances, -1))
def reshape_data_to_view(self, data: torch.Tensor) -> torch.Tensor:
"""Reshapes and arranges the data to the be consistent with data from the :attr:`root_physx_view`.
Args:
data: The data to be reshaped. Shape is (num_instances, num_objects, data_size).
Returns:
The reshaped data. Shape is (num_instances*num_objects, data_size).
"""
return torch.einsum("ijk -> jik", data).reshape(self.num_objects * self.num_instances, *data.shape[2:])
def _env_obj_ids_to_view_ids(
self, env_ids: torch.Tensor, object_ids: Sequence[int] | slice | torch.Tensor
) -> torch.Tensor:
......
......@@ -73,10 +73,19 @@ class RigidObjectCollectionData:
)
# Initialize the lazy buffers.
# -- link frame w.r.t. world frame
self._object_link_pose_w = TimestampedBuffer()
self._object_link_vel_w = TimestampedBuffer()
# -- com frame w.r.t. link frame
self._object_com_pose_b = TimestampedBuffer()
# -- com frame w.r.t. world frame
self._object_com_pose_w = TimestampedBuffer()
self._object_com_vel_w = TimestampedBuffer()
self._object_com_acc_w = TimestampedBuffer()
# -- combined state(these are cached as they concatenate)
self._object_state_w = TimestampedBuffer()
self._object_link_state_w = TimestampedBuffer()
self._object_com_state_w = TimestampedBuffer()
self._object_acc_w = TimestampedBuffer()
def update(self, dt: float):
"""Updates the data for the rigid object collection.
......@@ -117,9 +126,76 @@ class RigidObjectCollectionData:
"""
##
# Properties.
# Root state properties.
##
@property
def object_link_pose_w(self):
"""Object link pose ``[pos, quat]`` in simulation world frame. Shape is (num_instances, num_objects, 7).
The position and orientation are of the rigid body's actor frame.
"""
if self._object_link_pose_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
# set the buffer data and timestamp
self._object_link_pose_w.data = pose
self._object_link_pose_w.timestamp = self._sim_timestamp
return self._object_link_pose_w.data
@property
def object_link_vel_w(self):
"""Object link velocity ``[lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, num_objects, 6).
The linear and angular velocities are of the rigid body's actor frame.
"""
if self._object_link_vel_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self.object_com_vel_w.clone()
# adjust linear velocity to link from center of mass
velocity[..., :3] += torch.linalg.cross(
velocity[..., 3:], math_utils.quat_rotate(self.object_link_quat_w, -self.object_com_pos_b), dim=-1
)
# set the buffer data and timestamp
self._object_link_vel_w.data = velocity
self._object_link_vel_w.timestamp = self._sim_timestamp
return self._object_link_vel_w.data
@property
def object_com_pose_w(self):
"""Object center of mass pose ``[pos, quat]`` in simulation world frame.
Shape is (num_instances, num_objects, 7).
The position and orientation are of the rigid body's center of mass frame.
"""
if self._object_com_pose_w.timestamp < self._sim_timestamp:
# adjust pose to center of mass
pos, quat = math_utils.combine_frame_transforms(
self.object_link_pos_w, self.object_link_quat_w, self.object_com_pos_b, self.object_com_quat_b
)
# set the buffer data and timestamp
self._object_com_pose_w.data = torch.cat((pos, quat), dim=-1)
self._object_com_pose_w.timestamp = self._sim_timestamp
return self._object_com_pose_w.data
@property
def object_com_vel_w(self):
"""Object center of mass velocity ``[lin_vel, ang_vel]`` in simulation world frame.
Shape is (num_instances, num_objects, 6).
The linear and angular velocities are of the rigid body's center of mass frame.
"""
if self._object_com_vel_w.timestamp < self._sim_timestamp:
self._object_com_vel_w.data = self._reshape_view_to_data(self._root_physx_view.get_velocities())
self._object_com_vel_w.timestamp = self._sim_timestamp
return self._object_com_vel_w.data
@property
def object_state_w(self):
"""Object state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame.
......@@ -128,15 +204,10 @@ class RigidObjectCollectionData:
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 self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
# set the buffer data and timestamp
self._object_state_w.data = torch.cat((pose, velocity), dim=-1)
self._object_state_w.data = torch.cat((self.object_link_pose_w, self.object_com_vel_w), dim=-1)
self._object_state_w.timestamp = self._sim_timestamp
return self._object_state_w.data
@property
......@@ -148,19 +219,9 @@ class RigidObjectCollectionData:
world.
"""
if self._object_link_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
# adjust linear velocity to link from center of mass
velocity[..., :3] += torch.linalg.cross(
velocity[..., 3:], math_utils.quat_apply(pose[..., 3:7], -self.com_pos_b[..., :]), dim=-1
)
# set the buffer data and timestamp
self._object_link_state_w.data = torch.cat((pose, velocity), dim=-1)
self._object_link_state_w.data = torch.cat((self.object_link_pose_w, self.object_link_vel_w), dim=-1)
self._object_link_state_w.timestamp = self._sim_timestamp
return self._object_link_state_w.data
@property
......@@ -169,36 +230,46 @@ class RigidObjectCollectionData:
Shape is (num_instances, num_objects, 13).
The position, quaternion, and linear/angular velocity are of the rigid body's center of mass frame
relative to the world. Center of mass frame is the orientation principle axes of inertia.
relative to the world. Center of mass frame has the orientation along the principle axes of inertia.
"""
if self._object_com_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
# adjust pose to center of mass
pos, quat = math_utils.combine_frame_transforms(
pose[..., :3], pose[..., 3:7], self.com_pos_b[..., :], self.com_quat_b[..., :]
)
# set the buffer data and timestamp
self._object_com_state_w.data = torch.cat((pos, quat, velocity), dim=-1)
self._object_com_state_w.data = torch.cat((self.object_com_pose_w, self.object_com_vel_w), dim=-1)
self._object_com_state_w.timestamp = self._sim_timestamp
return self._object_com_state_w.data
@property
def object_acc_w(self):
def object_com_acc_w(self):
"""Acceleration of all objects. Shape is (num_instances, num_objects, 6).
This quantity is the acceleration of the rigid bodies' center of mass frame.
"""
if self._object_acc_w.timestamp < self._sim_timestamp:
# note: we use finite differencing to compute acceleration
self._object_acc_w.data = self._reshape_view_to_data(self._root_physx_view.get_accelerations().clone())
self._object_acc_w.timestamp = self._sim_timestamp
return self._object_acc_w.data
if self._object_com_acc_w.timestamp < self._sim_timestamp:
self._object_com_acc_w.data = self._reshape_view_to_data(self._root_physx_view.get_accelerations())
self._object_com_acc_w.timestamp = self._sim_timestamp
return self._object_com_acc_w.data
@property
def object_com_pose_b(self):
"""Object center of mass pose ``[pos, quat]`` in their respective body's link frame.
Shape is (num_instances, num_objects, 7).
The position and orientation are of the rigid body's center of mass frame.
The orientation is provided in (w, x, y, z) format.
"""
if self._object_com_pose_b.timestamp < self._sim_timestamp:
# obtain the coms
poses = self._root_physx_view.get_coms().to(self.device)
poses[:, 3:7] = math_utils.convert_quat(poses[:, 3:7], to="wxyz")
# read data from simulation
self._object_com_pose_b.data = self._reshape_view_to_data(poses)
self._object_com_pose_b.timestamp = self._sim_timestamp
return self._object_com_pose_b.data
##
# Derived properties.
##
@property
def projected_gravity_b(self):
......@@ -216,83 +287,45 @@ class RigidObjectCollectionData:
forward_w = math_utils.quat_apply(self.object_link_quat_w, self.FORWARD_VEC_B)
return torch.atan2(forward_w[..., 1], forward_w[..., 0])
##
# Derived properties.
##
@property
def object_pos_w(self) -> torch.Tensor:
"""Object position in simulation world frame. Shape is (num_instances, num_objects, 3).
This quantity is the position of the actor frame of the rigid bodies.
"""
return self.object_state_w[..., :3]
@property
def object_quat_w(self) -> torch.Tensor:
"""Object orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, num_objects, 4).
This quantity is the orientation of the actor frame of the rigid bodies.
"""
return self.object_state_w[..., 3:7]
@property
def object_vel_w(self) -> torch.Tensor:
"""Object velocity in simulation world frame. Shape is (num_instances, num_objects, 6).
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
"""
return self.object_state_w[..., 7:13]
@property
def object_lin_vel_w(self) -> torch.Tensor:
"""Object linear velocity in simulation world frame. Shape is (num_instances, num_objects, 3).
This quantity is the linear velocity of the rigid bodies' center of mass frame.
"""
return self.object_state_w[..., 7:10]
@property
def object_ang_vel_w(self) -> torch.Tensor:
"""Object angular velocity in simulation world frame. Shape is (num_instances, num_objects, 3).
def object_link_lin_vel_b(self) -> torch.Tensor:
"""Object link linear velocity in base frame. Shape is (num_instances, num_objects, 3).
This quantity is the angular velocity of the rigid bodies' center of mass frame.
This quantity is the linear velocity of the actor frame of the root rigid body frame with
respect to the rigid body's actor frame.
"""
return self.object_state_w[..., 10:13]
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_link_lin_vel_w)
@property
def object_lin_vel_b(self) -> torch.Tensor:
"""Object linear velocity in base frame. Shape is (num_instances, num_objects, 3).
def object_link_ang_vel_b(self) -> torch.Tensor:
"""Object link angular velocity in base world frame. Shape is (num_instances, num_objects, 3).
This quantity is the linear velocity of the rigid bodies' center of mass frame with respect to the
rigid body's actor frame.
This quantity is the angular velocity of the actor frame of the root rigid body frame with
respect to the rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.object_quat_w, self.object_lin_vel_w)
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_link_ang_vel_w)
@property
def object_ang_vel_b(self) -> torch.Tensor:
"""Object angular velocity in base world frame. Shape is (num_instances, num_objects, 3).
def object_com_lin_vel_b(self) -> torch.Tensor:
"""Object center of mass linear velocity in base frame. Shape is (num_instances, num_objects, 3).
This quantity is the angular velocity of the rigid bodies' center of mass frame with respect to the
rigid body's actor frame.
This quantity is the linear velocity of the center of mass frame of the root rigid body frame with
respect to the rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.object_quat_w, self.object_ang_vel_w)
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_com_lin_vel_w)
@property
def object_lin_acc_w(self) -> torch.Tensor:
"""Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_objects, 3).
def object_com_ang_vel_b(self) -> torch.Tensor:
"""Object center of mass angular velocity in base world frame. Shape is (num_instances, num_objects, 3).
This quantity is the linear acceleration of the rigid bodies' center of mass frame.
This quantity is the angular velocity of the center of mass frame of the root rigid body frame with
respect to the rigid body's actor frame.
"""
return self.object_acc_w[..., 0:3]
@property
def object_ang_acc_w(self) -> torch.Tensor:
"""Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_objects, 3).
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_com_ang_vel_w)
This quantity is the angular acceleration of the rigid bodies' center of mass frame.
"""
return self.object_acc_w[..., 3:6]
##
# Sliced properties.
##
@property
def object_link_pos_w(self) -> torch.Tensor:
......@@ -300,11 +333,7 @@ class RigidObjectCollectionData:
This quantity is the position of the actor frame of the rigid bodies.
"""
if self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
return pose[..., :3]
return self.object_link_state_w[..., :3]
return self.object_link_pose_w[..., :3]
@property
def object_link_quat_w(self) -> torch.Tensor:
......@@ -312,20 +341,7 @@ class RigidObjectCollectionData:
This quantity is the orientation of the actor frame of the rigid bodies.
"""
if self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
pose = self._reshape_view_to_data(self._root_physx_view.get_transforms().clone())
pose[..., 3:7] = math_utils.convert_quat(pose[..., 3:7], to="wxyz")
return pose[..., 3:7]
return self.object_link_state_w[..., 3:7]
@property
def object_link_vel_w(self) -> torch.Tensor:
"""Object link velocity in simulation world frame. Shape is (num_instances, num_objects, 6).
This quantity contains the linear and angular velocities of the rigid bodies' actor frame.
"""
return self.object_link_state_w[..., 7:13]
return self.object_link_pose_w[..., 3:7]
@property
def object_link_lin_vel_w(self) -> torch.Tensor:
......@@ -333,7 +349,7 @@ class RigidObjectCollectionData:
This quantity is the linear velocity of the rigid bodies' actor frame.
"""
return self.object_link_state_w[..., 7:10]
return self.object_link_vel_w[..., :3]
@property
def object_link_ang_vel_w(self) -> torch.Tensor:
......@@ -341,25 +357,7 @@ class RigidObjectCollectionData:
This quantity is the angular velocity of the rigid bodies' actor frame.
"""
return self.object_link_state_w[..., 10:13]
@property
def object_link_lin_vel_b(self) -> torch.Tensor:
"""Object link linear velocity in base frame. Shape is (num_instances, num_objects, 3).
This quantity is the linear velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_link_lin_vel_w)
@property
def object_link_ang_vel_b(self) -> torch.Tensor:
"""Object link angular velocity in base world frame. Shape is (num_instances, num_objects, 3).
This quantity is the angular velocity of the actor frame of the root rigid body frame with respect to the
rigid body's actor frame.
"""
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_link_ang_vel_w)
return self.object_link_vel_w[..., 3:6]
@property
def object_com_pos_w(self) -> torch.Tensor:
......@@ -367,27 +365,16 @@ class RigidObjectCollectionData:
This quantity is the position of the center of mass frame of the rigid bodies.
"""
return self.object_com_state_w[..., :3]
return self.object_com_pose_w[..., :3]
@property
def object_com_quat_w(self) -> torch.Tensor:
"""Object center of mass orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, num_objects, 4).
"""Object center of mass orientation (w, x, y, z) in simulation world frame.
Shape is (num_instances, num_objects, 4).
This quantity is the orientation of the center of mass frame of the rigid bodies.
"""
return self.object_com_state_w[..., 3:7]
@property
def object_com_vel_w(self) -> torch.Tensor:
"""Object center of mass velocity in simulation world frame. Shape is (num_instances, num_objects, 6).
This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
"""
if self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
return velocity
return self.object_com_state_w[..., 7:13]
return self.object_com_pose_w[..., 3:7]
@property
def object_com_lin_vel_w(self) -> torch.Tensor:
......@@ -395,11 +382,7 @@ class RigidObjectCollectionData:
This quantity is the linear velocity of the rigid bodies' center of mass frame.
"""
if self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
return velocity[..., 0:3]
return self.object_com_state_w[..., 7:10]
return self.object_com_vel_w[..., :3]
@property
def object_com_ang_vel_w(self) -> torch.Tensor:
......@@ -407,48 +390,113 @@ class RigidObjectCollectionData:
This quantity is the angular velocity of the rigid bodies' center of mass frame.
"""
if self._object_state_w.timestamp < self._sim_timestamp:
# read data from simulation
velocity = self._reshape_view_to_data(self._root_physx_view.get_velocities())
return velocity[..., 3:6]
return self.object_com_state_w[..., 10:13]
return self.object_com_vel_w[..., 3:6]
@property
def object_com_lin_vel_b(self) -> torch.Tensor:
"""Object center of mass linear velocity in base frame. Shape is (num_instances, num_objects, 3).
def object_com_lin_acc_w(self) -> torch.Tensor:
"""Object center of mass linear acceleration in simulation world frame.
Shape is (num_instances, num_objects, 3).
This quantity is the linear velocity of the center of mass frame of the root rigid body frame with respect to the
rigid body's actor frame.
This quantity is the linear acceleration of the rigid bodies' center of mass frame.
"""
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_com_lin_vel_w)
return self.object_com_acc_w[..., :3]
@property
def object_com_ang_vel_b(self) -> torch.Tensor:
"""Object center of mass angular velocity in base world frame. Shape is (num_instances, num_objects, 3).
def object_com_ang_acc_w(self) -> torch.Tensor:
"""Object center of mass angular acceleration in simulation world frame.
Shape is (num_instances, num_objects, 3).
This quantity is the angular velocity of the center of mass frame of the root rigid body frame with respect to the
rigid body's actor frame.
This quantity is the angular acceleration of the rigid bodies' center of mass frame.
"""
return math_utils.quat_apply_inverse(self.object_link_quat_w, self.object_com_ang_vel_w)
return self.object_com_acc_w[..., 3:6]
@property
def com_pos_b(self) -> torch.Tensor:
"""Center of mass of all of the bodies in simulation world frame. Shape is (num_instances, 1, 3).
def object_com_pos_b(self) -> torch.Tensor:
"""Center of mass of all of the bodies in their respective body's link frame.
Shape is (num_instances, num_objects, 3).
This quantity is the center of mass location relative to its body frame.
This quantity is the center of mass location relative to its body link frame.
"""
pos = self._root_physx_view.get_coms().to(self.device)[..., :3]
return self._reshape_view_to_data(pos)
return self.object_com_pose_b[..., :3]
@property
def com_quat_b(self) -> torch.Tensor:
"""Orientation (w,x,y,z) of the prinicple axies of inertia of all of the bodies in simulation world frame. Shape is (num_instances, 1, 4).
def object_com_quat_b(self) -> torch.Tensor:
"""Orientation (w,x,y,z) of the principle axis of inertia of all of the bodies in simulation world frame.
Shape is (num_instances, num_objects, 4).
This quantity is the orientation of the principles axes of inertia relative to its body frame.
This quantity is the orientation of the principles axes of inertia relative to its body link frame.
The orientation is provided in (w, x, y, z) format.
"""
quat = self._root_physx_view.get_coms().to(self.device)[..., 3:7].view(self.num_instances, self.num_objects, 4)
quat_wxyz = math_utils.convert_quat(quat, to="wxyz")
return self._reshape_view_to_data(quat_wxyz)
return self.object_com_pose_b[..., 3:7]
##
# Properties for backwards compatibility.
##
@property
def object_pose_w(self) -> torch.Tensor:
"""Same as :attr:`object_link_pose_w`."""
return self.object_link_pose_w
@property
def object_pos_w(self) -> torch.Tensor:
"""Same as :attr:`object_link_pos_w`."""
return self.object_link_pos_w
@property
def object_quat_w(self) -> torch.Tensor:
"""Same as :attr:`object_link_quat_w`."""
return self.object_link_quat_w
@property
def object_vel_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_vel_w`."""
return self.object_com_vel_w
@property
def object_lin_vel_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_lin_vel_w`."""
return self.object_com_lin_vel_w
@property
def object_ang_vel_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_ang_vel_w`."""
return self.object_com_ang_vel_w
@property
def object_lin_vel_b(self) -> torch.Tensor:
"""Same as :attr:`object_com_lin_vel_b`."""
return self.object_com_lin_vel_b
@property
def object_ang_vel_b(self) -> torch.Tensor:
"""Same as :attr:`object_com_ang_vel_b`."""
return self.object_com_ang_vel_b
@property
def object_acc_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_acc_w`."""
return self.object_com_acc_w
@property
def object_lin_acc_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_lin_acc_w`."""
return self.object_com_lin_acc_w
@property
def object_ang_acc_w(self) -> torch.Tensor:
"""Same as :attr:`object_com_ang_acc_w`."""
return self.object_com_ang_acc_w
@property
def com_pos_b(self) -> torch.Tensor:
"""Same as :attr:`object_com_pos_b`."""
return self.object_com_pos_b
@property
def com_quat_b(self) -> torch.Tensor:
"""Same as :attr:`object_com_quat_b`."""
return self.object_com_quat_b
##
# Helpers.
......
......@@ -106,8 +106,8 @@ class UniformPoseCommand(CommandTerm):
pos_error, rot_error = compute_pose_error(
self.pose_command_w[:, :3],
self.pose_command_w[:, 3:],
self.robot.data.body_state_w[:, self.body_idx, :3],
self.robot.data.body_state_w[:, self.body_idx, 3:7],
self.robot.data.body_pos_w[:, self.body_idx],
self.robot.data.body_quat_w[:, self.body_idx],
)
self.metrics["position_error"] = torch.norm(pos_error, dim=-1)
self.metrics["orientation_error"] = torch.norm(rot_error, dim=-1)
......@@ -156,5 +156,5 @@ class UniformPoseCommand(CommandTerm):
# -- goal pose
self.goal_pose_visualizer.visualize(self.pose_command_w[:, :3], self.pose_command_w[:, 3:])
# -- current body pose
body_link_state_w = self.robot.data.body_state_w[:, self.body_idx]
self.current_pose_visualizer.visualize(body_link_state_w[:, :3], body_link_state_w[:, 3:7])
body_link_pose_w = self.robot.data.body_link_pose_w[:, self.body_idx]
self.current_pose_visualizer.visualize(body_link_pose_w[:, :3], body_link_pose_w[:, 3:7])
......@@ -150,7 +150,7 @@ def body_projected_gravity_b(
body_quat = asset.data.body_quat_w[:, asset_cfg.body_ids]
gravity_dir = asset.data.GRAVITY_VEC_W.unsqueeze(1)
return math_utils.quat_rotate_inverse(body_quat, gravity_dir).view(env.num_envs, -1)
return math_utils.quat_apply_inverse(body_quat, gravity_dir).view(env.num_envs, -1)
"""
......
......@@ -543,7 +543,7 @@ class InteractiveScene:
state["articulation"] = dict()
for asset_name, articulation in self._articulations.items():
asset_state = dict()
asset_state["root_pose"] = articulation.data.root_state_w[:, :7].clone()
asset_state["root_pose"] = articulation.data.root_pose_w.clone()
if is_relative:
asset_state["root_pose"][:, :3] -= self.env_origins
asset_state["root_velocity"] = articulation.data.root_vel_w.clone()
......@@ -563,7 +563,7 @@ class InteractiveScene:
state["rigid_object"] = dict()
for asset_name, rigid_object in self._rigid_objects.items():
asset_state = dict()
asset_state["root_pose"] = rigid_object.data.root_state_w[:, :7].clone()
asset_state["root_pose"] = rigid_object.data.root_pose_w.clone()
if is_relative:
asset_state["root_pose"][:, :3] -= self.env_origins
asset_state["root_velocity"] = rigid_object.data.root_vel_w.clone()
......
......@@ -1407,7 +1407,7 @@ def test_body_root_state(sim, num_articulations, device, with_offset):
torch.testing.assert_close(pos_gt, body_com_state_w[..., :3], atol=1e-3, rtol=1e-1)
# orientation
com_quat_b = articulation.data.com_quat_b
com_quat_b = articulation.data.body_com_quat_b
com_quat_w = math_utils.quat_mul(body_link_state_w[..., 3:7], com_quat_b)
torch.testing.assert_close(com_quat_w, body_com_state_w[..., 3:7])
torch.testing.assert_close(com_quat_w[:, 0, :], root_com_state_w[..., 3:7])
......
......@@ -812,7 +812,7 @@ def test_body_root_state_properties(num_cubes, device, with_offset):
else:
# cubes are spinning around center of mass
# position will not match
# center of mass position will be constant (i.e. spining around com)
# center of mass position will be constant (i.e. spinning around com)
torch.testing.assert_close(env_pos + offset, root_com_state_w[..., :3])
torch.testing.assert_close(env_pos + offset, body_com_state_w[..., :3].squeeze(-2))
# link position will be moving but should stay constant away from center of mass
......@@ -828,7 +828,7 @@ def test_body_root_state_properties(num_cubes, device, with_offset):
torch.testing.assert_close(-offset, body_link_state_pos_rel_com.squeeze(-2))
# orientation of com will be a constant rotation from link orientation
com_quat_b = cube_object.data.com_quat_b
com_quat_b = cube_object.data.body_com_quat_b
com_quat_w = quat_mul(body_link_state_w[..., 3:7], com_quat_b)
torch.testing.assert_close(com_quat_w, body_com_state_w[..., 3:7])
torch.testing.assert_close(com_quat_w.squeeze(-2), root_com_state_w[..., 3:7])
......@@ -838,7 +838,7 @@ def test_body_root_state_properties(num_cubes, device, with_offset):
torch.testing.assert_close(body_state_w[..., 3:7], body_link_state_w[..., 3:7])
# lin_vel will not match
# center of mass vel will be constant (i.e. spining around com)
# center of mass vel will be constant (i.e. spinning around com)
torch.testing.assert_close(torch.zeros_like(root_com_state_w[..., 7:10]), root_com_state_w[..., 7:10])
torch.testing.assert_close(torch.zeros_like(body_com_state_w[..., 7:10]), body_com_state_w[..., 7:10])
# link frame will be moving, and should be equal to input angular velocity cross offset
......@@ -883,7 +883,7 @@ def test_write_root_state(num_cubes, device, with_offset, state_location):
com[..., :3] = offset.to("cpu")
cube_object.root_physx_view.set_coms(com, env_idx)
# check ceter of mass has been set
# check center of mass has been set
torch.testing.assert_close(cube_object.root_physx_view.get_coms(), com)
rand_state = torch.zeros_like(cube_object.data.root_state_w)
......
......@@ -402,7 +402,7 @@ def test_object_state_properties(sim, num_envs, num_cubes, device, with_offset,
for i in range(10):
# spin the object around Z axis (com)
cube_object.write_object_com_velocity_to_sim(spin_twist.repeat(num_envs, num_cubes, 1))
cube_object.write_object_velocity_to_sim(spin_twist.repeat(num_envs, num_cubes, 1))
sim.step()
cube_object.update(sim.cfg.dt)
......@@ -430,7 +430,7 @@ def test_object_state_properties(sim, num_envs, num_cubes, device, with_offset,
torch.testing.assert_close(-offset, object_link_state_pos_rel_com)
# orientation of com will be a constant rotation from link orientation
com_quat_b = cube_object.data.com_quat_b
com_quat_b = cube_object.data.object_com_quat_b
com_quat_w = quat_mul(object_link_state_w[..., 3:7], com_quat_b)
torch.testing.assert_close(com_quat_w, object_com_state_w[..., 3:7])
......
......@@ -164,8 +164,8 @@ def _run_ik_controller(
ee_pose_b_des = torch.zeros(num_envs, diff_ik_controller.action_dim, device=sim.device)
ee_pose_b_des[:] = ee_pose_b_des_set[current_goal_idx]
# Compute current pose of the end-effector
ee_pose_w = robot.data.body_state_w[:, ee_frame_idx, 0:7]
root_pose_w = robot.data.root_state_w[:, 0:7]
ee_pose_w = robot.data.body_pose_w[:, ee_frame_idx]
root_pose_w = robot.data.root_pose_w
ee_pos_b, ee_quat_b = subtract_frame_transforms(
root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_pose_w[:, 0:3], ee_pose_w[:, 3:7]
)
......@@ -212,8 +212,8 @@ def _run_ik_controller(
# so we MUST skip the first step
# obtain quantities from simulation
jacobian = robot.root_physx_view.get_jacobians()[:, ee_jacobi_idx, :, arm_joint_ids]
ee_pose_w = robot.data.body_state_w[:, ee_frame_idx, 0:7]
root_pose_w = robot.data.root_state_w[:, 0:7]
ee_pose_w = robot.data.body_pose_w[:, ee_frame_idx]
root_pose_w = robot.data.root_pose_w
base_rot = root_pose_w[:, 3:7]
base_rot_matrix = matrix_from_quat(quat_inv(base_rot))
jacobian[:, :3, :] = torch.bmm(base_rot_matrix, jacobian[:, :3, :])
......
......@@ -1416,8 +1416,8 @@ def _update_states(
jacobian_b[:, 3:, :] = torch.bmm(root_rot_matrix, jacobian_b[:, 3:, :])
# Compute current pose of the end-effector
root_pose_w = robot.data.root_state_w[:, 0:7]
ee_pose_w = robot.data.body_state_w[:, ee_frame_idx, 0:7]
root_pose_w = robot.data.root_pose_w
ee_pose_w = robot.data.body_pose_w[:, ee_frame_idx]
ee_pos_b, ee_quat_b = subtract_frame_transforms(
root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_pose_w[:, 0:3], ee_pose_w[:, 3:7]
)
......
......@@ -186,7 +186,7 @@ def test_frame_transformer_feet_wrt_base(sim):
# check absolute frame transforms in world frame
# -- ground-truth
root_pose_w = scene.articulations["robot"].data.root_state_w[:, :7]
root_pose_w = scene.articulations["robot"].data.root_pose_w
feet_pos_w_gt = scene.articulations["robot"].data.body_pos_w[:, feet_indices]
feet_quat_w_gt = scene.articulations["robot"].data.body_quat_w[:, feet_indices]
# -- frame transformer
......@@ -362,9 +362,9 @@ def test_frame_transformer_robot_body_to_external_cube(sim):
# check absolute frame transforms in world frame
# -- ground-truth
root_pose_w = scene.articulations["robot"].data.root_state_w[:, :7]
cube_pos_w_gt = scene.rigid_objects["cube"].data.root_state_w[:, :3]
cube_quat_w_gt = scene.rigid_objects["cube"].data.root_state_w[:, 3:7]
root_pose_w = scene.articulations["robot"].data.root_pose_w
cube_pos_w_gt = scene.rigid_objects["cube"].data.root_pos_w
cube_quat_w_gt = scene.rigid_objects["cube"].data.root_quat_w
# -- frame transformer
source_pos_w_tf = scene.sensors["frame_transformer"].data.source_pos_w
source_quat_w_tf = scene.sensors["frame_transformer"].data.source_quat_w
......@@ -451,8 +451,8 @@ def test_frame_transformer_offset_frames(sim):
# check absolute frame transforms in world frame
# -- ground-truth
cube_pos_w_gt = scene["cube"].data.root_state_w[:, :3]
cube_quat_w_gt = scene["cube"].data.root_state_w[:, 3:7]
cube_pos_w_gt = scene["cube"].data.root_pos_w
cube_quat_w_gt = scene["cube"].data.root_quat_w
# -- frame transformer
source_pos_w_tf = scene.sensors["frame_transformer"].data.source_pos_w
source_quat_w_tf = scene.sensors["frame_transformer"].data.source_quat_w
......@@ -544,7 +544,7 @@ def test_frame_transformer_all_bodies(sim):
# check absolute frame transforms in world frame
# -- ground-truth
root_pose_w = scene.articulations["robot"].data.root_state_w[:, :7]
root_pose_w = scene.articulations["robot"].data.root_pose_w
bodies_pos_w_gt = scene.articulations["robot"].data.body_pos_w
bodies_quat_w_gt = scene.articulations["robot"].data.body_quat_w
......
......@@ -157,7 +157,7 @@ class QuadcopterEnv(DirectRLEnv):
def _get_observations(self) -> dict:
desired_pos_b, _ = subtract_frame_transforms(
self._robot.data.root_state_w[:, :3], self._robot.data.root_state_w[:, 3:7], self._desired_pos_w
self._robot.data.root_pos_w, self._robot.data.root_quat_w, self._desired_pos_w
)
obs = torch.cat(
[
......
......@@ -30,7 +30,5 @@ def object_position_in_robot_root_frame(
robot: RigidObject = env.scene[robot_cfg.name]
object: RigidObject = env.scene[object_cfg.name]
object_pos_w = object.data.root_pos_w[:, :3]
object_pos_b, _ = subtract_frame_transforms(
robot.data.root_state_w[:, :3], robot.data.root_state_w[:, 3:7], object_pos_w
)
object_pos_b, _ = subtract_frame_transforms(robot.data.root_pos_w, robot.data.root_quat_w, object_pos_w)
return object_pos_b
......@@ -65,8 +65,8 @@ def object_goal_distance(
command = env.command_manager.get_command(command_name)
# compute the desired position in the world frame
des_pos_b = command[:, :3]
des_pos_w, _ = combine_frame_transforms(robot.data.root_state_w[:, :3], robot.data.root_state_w[:, 3:7], des_pos_b)
des_pos_w, _ = combine_frame_transforms(robot.data.root_pos_w, robot.data.root_quat_w, des_pos_b)
# distance of the end-effector to the object: (num_envs,)
distance = torch.norm(des_pos_w - object.data.root_pos_w[:, :3], dim=1)
distance = torch.norm(des_pos_w - object.data.root_pos_w, dim=1)
# rewarded if the object is lifted above the threshold
return (object.data.root_pos_w[:, 2] > minimal_height) * (1 - torch.tanh(distance / std))
......@@ -50,7 +50,7 @@ def object_reached_goal(
command = env.command_manager.get_command(command_name)
# compute the desired position in the world frame
des_pos_b = command[:, :3]
des_pos_w, _ = combine_frame_transforms(robot.data.root_state_w[:, :3], robot.data.root_state_w[:, 3:7], des_pos_b)
des_pos_w, _ = combine_frame_transforms(robot.data.root_pos_w, robot.data.root_quat_w, des_pos_b)
# distance of the end-effector to the object: (num_envs,)
distance = torch.norm(des_pos_w - object.data.root_pos_w[:, :3], dim=1)
......
......@@ -33,8 +33,8 @@ def position_command_error(env: ManagerBasedRLEnv, command_name: str, asset_cfg:
command = env.command_manager.get_command(command_name)
# obtain the desired and current positions
des_pos_b = command[:, :3]
des_pos_w, _ = combine_frame_transforms(asset.data.root_state_w[:, :3], asset.data.root_state_w[:, 3:7], des_pos_b)
curr_pos_w = asset.data.body_state_w[:, asset_cfg.body_ids[0], :3] # type: ignore
des_pos_w, _ = combine_frame_transforms(asset.data.root_pos_w, asset.data.root_quat_w, des_pos_b)
curr_pos_w = asset.data.body_pos_w[:, asset_cfg.body_ids[0]] # type: ignore
return torch.norm(curr_pos_w - des_pos_w, dim=1)
......@@ -51,8 +51,8 @@ def position_command_error_tanh(
command = env.command_manager.get_command(command_name)
# obtain the desired and current positions
des_pos_b = command[:, :3]
des_pos_w, _ = combine_frame_transforms(asset.data.root_state_w[:, :3], asset.data.root_state_w[:, 3:7], des_pos_b)
curr_pos_w = asset.data.body_state_w[:, asset_cfg.body_ids[0], :3] # type: ignore
des_pos_w, _ = combine_frame_transforms(asset.data.root_pos_w, asset.data.root_quat_w, des_pos_b)
curr_pos_w = asset.data.body_pos_w[:, asset_cfg.body_ids[0]] # type: ignore
distance = torch.norm(curr_pos_w - des_pos_w, dim=1)
return 1 - torch.tanh(distance / std)
......@@ -69,6 +69,6 @@ def orientation_command_error(env: ManagerBasedRLEnv, command_name: str, asset_c
command = env.command_manager.get_command(command_name)
# obtain the desired and current orientations
des_quat_b = command[:, 3:7]
des_quat_w = quat_mul(asset.data.root_state_w[:, 3:7], des_quat_b)
curr_quat_w = asset.data.body_state_w[:, asset_cfg.body_ids[0], 3:7] # type: ignore
des_quat_w = quat_mul(asset.data.root_quat_w, des_quat_b)
curr_quat_w = asset.data.body_quat_w[:, asset_cfg.body_ids[0]] # type: ignore
return quat_error_magnitude(curr_quat_w, des_quat_w)
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