Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
632c29d
Migrate camera/renderer/camdata to warp/proxyarray
StafaH May 11, 2026
26c1c86
Fix .torch for math functions
StafaH May 12, 2026
6244ce9
Convert torch operations to warp inside camera
StafaH May 12, 2026
f07a645
Fix failing tests
StafaH May 12, 2026
ab109de
Ruff format
StafaH May 12, 2026
5e4bc67
MR comments
StafaH May 12, 2026
aa1eb06
Fix ruff check
StafaH May 12, 2026
0f2d3b5
Merge branch 'develop' into mh/warp_cam
StafaH May 13, 2026
54aca63
Merge branch 'develop' into mh/warp_cam
StafaH May 13, 2026
5672ebe
Merge branch 'develop' into mh/warp_cam
kellyguo11 May 14, 2026
c011486
Merge branch 'develop' into mh/warp_cam
kellyguo11 May 14, 2026
b03897f
Merge branch 'develop' into mh/warp_cam
kellyguo11 May 14, 2026
de53ea1
Fix interop between raycaster with CameraData
StafaH May 14, 2026
b8b84fa
Fix failing tests in isaaclab core
StafaH May 14, 2026
0b90700
Merge branch 'develop' into mh/warp_cam
StafaH May 14, 2026
b206201
Merge branch 'develop' into mh/warp_cam
kellyguo11 May 15, 2026
45058d9
Fix tests assuming torch output
StafaH May 15, 2026
b08de57
Skip changelog fragment for test fix
StafaH May 15, 2026
4933fff
Remove leapp semantics from this PR
StafaH May 15, 2026
3b4b2cd
Merge branch 'develop' into mh/warp_cam
StafaH May 15, 2026
b6a3073
Fix image test bug
StafaH May 16, 2026
cef8706
Merge branch 'develop' into mh/warp_cam
StafaH May 16, 2026
c17cd38
Fix ovrtx_renderer import order
StafaH May 16, 2026
e913585
Merge branch 'develop' into mh/warp_cam
StafaH May 16, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions source/isaaclab/changelog.d/mh-warp_cam.minor.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
Changed
^^^^^^^

* Changed :class:`~isaaclab.sensors.camera.CameraData` to expose all sensor buffers as
:class:`~isaaclab.utils.warp.ProxyArray` instead of :class:`torch.Tensor`. The fields
:attr:`~isaaclab.sensors.camera.CameraData.pos_w` (``wp.vec3f``),
:attr:`~isaaclab.sensors.camera.CameraData.quat_w_world` (``wp.quatf``),
:attr:`~isaaclab.sensors.camera.CameraData.intrinsic_matrices` (``wp.mat33f``), and all
entries in :attr:`~isaaclab.sensors.camera.CameraData.output` are now backed by warp arrays.
Use ``.torch`` for a zero-copy :class:`torch.Tensor` view or ``.warp`` to pass the array
directly to a warp kernel. Existing code using these fields as tensors (indexing, arithmetic,
:func:`torch.testing.assert_close`, etc.) continues to work via the
:class:`~isaaclab.utils.warp.ProxyArray` deprecation bridge with a one-time
:class:`DeprecationWarning`.
* Updated :meth:`~isaaclab.renderers.BaseRenderer.set_outputs` and
:meth:`~isaaclab.renderers.BaseRenderer.update_camera` in :class:`~isaaclab.renderers.BaseRenderer`
to accept :class:`~isaaclab.utils.warp.ProxyArray` arguments instead of :class:`torch.Tensor`.
24 changes: 16 additions & 8 deletions source/isaaclab/isaaclab/renderers/base_renderer.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,8 @@
from .output_contract import RenderBufferKind, RenderBufferSpec

if TYPE_CHECKING:
import torch

from isaaclab.sensors.camera.camera_data import CameraData
from isaaclab.utils.warp import ProxyArray


class BaseRenderer(ABC):
Expand Down Expand Up @@ -64,13 +63,15 @@ def create_render_data(self, spec: CameraRenderSpec) -> Any:
pass

@abstractmethod
def set_outputs(self, render_data: Any, output_data: dict[str, torch.Tensor]) -> None:
def set_outputs(self, render_data: Any, output_data: dict[str, ProxyArray]) -> None:
"""Store reference to output buffers for writing during render.

Args:
render_data: The render data object from :meth:`create_render_data`.
output_data: Dictionary mapping output names (e.g. ``"rgb"``, ``"depth"``)
to pre-allocated tensors where rendered data will be written.
to pre-allocated :class:`~isaaclab.utils.warp.ProxyArray` wrappers where
rendered data will be written. Use ``.warp`` for the underlying warp array
or ``.torch`` for a zero-copy tensor view.
"""
pass

Expand All @@ -84,15 +85,22 @@ def update_transforms(self) -> None:

@abstractmethod
def update_camera(
self, render_data: Any, positions: torch.Tensor, orientations: torch.Tensor, intrinsics: torch.Tensor
self,
render_data: Any,
positions: ProxyArray,
orientations: ProxyArray,
intrinsics: ProxyArray,
) -> None:
"""Update camera poses and intrinsics for the next render.

Args:
render_data: The render data object from :meth:`create_render_data`.
positions: Camera positions in world frame, shape ``(N, 3)``.
orientations: Camera orientations as quaternions (x, y, z, w), shape ``(N, 4)``.
intrinsics: Camera intrinsic matrices, shape ``(N, 3, 3)``.
positions: Camera positions in world frame. Shape ``(N,)``, dtype ``wp.vec3f``.
Use ``.torch`` for a ``(N, 3)`` tensor view.
orientations: Camera orientations as quaternions ``(x, y, z, w)``. Shape ``(N,)``,
dtype ``wp.quatf``. Use ``.torch`` for a ``(N, 4)`` tensor view.
intrinsics: Camera intrinsic matrices. Shape ``(N,)``, dtype ``wp.mat33f``.
Use ``.torch`` for a ``(N, 3, 3)`` tensor view.
"""
pass

Expand Down
10 changes: 3 additions & 7 deletions source/isaaclab/isaaclab/renderers/output_contract.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,6 @@

from dataclasses import dataclass
from enum import StrEnum
from typing import TYPE_CHECKING

if TYPE_CHECKING:
import torch


class RenderBufferKind(StrEnum):
Expand Down Expand Up @@ -48,7 +44,7 @@ class RenderBufferSpec:
"""Per-pixel layout (channels + dtype) for one render buffer kind."""

channels: int
"""Number of per-pixel channels (last dimension of the allocated tensor)."""
"""Number of per-pixel channels (last dimension of the allocated warp array)."""

dtype: torch.dtype
"""Torch dtype the renderer writes for this render buffer kind."""
dtype: type
"""Warp scalar dtype for the buffer (e.g. ``wp.float32``, ``wp.uint8``)."""
37 changes: 24 additions & 13 deletions source/isaaclab/isaaclab/sensors/camera/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
create_rotation_matrix_from_view,
quat_from_matrix,
)
from isaaclab.utils.warp.warp_math import convert_camera_frame_orientation_convention_wp

from ..sensor_base import SensorBase
from .camera_data import CameraData, RenderBufferKind
Expand Down Expand Up @@ -508,6 +509,7 @@ def _create_buffers(self):
type(self._renderer).__name__,
unsupported,
)
device_str = self._device if isinstance(self._device, str) else str(self._device)
self._data = CameraData.allocate(
data_types=known,
height=self.cfg.height,
Expand All @@ -517,11 +519,9 @@ def _create_buffers(self):
supported_specs=specs,
)
# Camera-frame state (pose / intrinsics) is owned by the camera, not
# the renderer: populate it on the freshly constructed ``CameraData``.
self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device)
# the renderer: allocate warp buffers and populate them.
self._data.create_buffers(self._view.count, device_str)
self._update_intrinsic_matrices(self._ALL_INDICES)
self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device)
self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device)
self._update_poses(self._ALL_INDICES)
self._renderer.set_outputs(self._render_data, self._data.output)

Expand Down Expand Up @@ -551,11 +551,12 @@ def _update_intrinsic_matrices(self, env_ids: Sequence[int]):
c_x = width * 0.5
c_y = height * 0.5
# create intrinsic matrix for depth linear
self._data.intrinsic_matrices[i, 0, 0] = f_x
self._data.intrinsic_matrices[i, 0, 2] = c_x
self._data.intrinsic_matrices[i, 1, 1] = f_y
self._data.intrinsic_matrices[i, 1, 2] = c_y
self._data.intrinsic_matrices[i, 2, 2] = 1
intrinsics_t = self._data.intrinsic_matrices.torch
intrinsics_t[i, 0, 0] = f_x
intrinsics_t[i, 0, 2] = c_x
intrinsics_t[i, 1, 1] = f_y
intrinsics_t[i, 1, 2] = c_y
intrinsics_t[i, 2, 2] = 1

def _update_poses(self, env_ids: Sequence[int]):
"""Computes the pose of the camera in the world frame with ROS convention.
Expand All @@ -570,14 +571,24 @@ def _update_poses(self, env_ids: Sequence[int]):
if len(self._sensor_prims) == 0:
raise RuntimeError("Camera prim is None. Please call 'sim.play()' first.")

# get the poses from the view (returns ProxyArray, use .torch for tensor access)
# get the poses from the view (returns ProxyArray)
if env_ids is not None and not isinstance(env_ids, torch.Tensor):
env_ids = torch.tensor(env_ids, dtype=torch.int32, device=self._device)
indices = wp.from_torch(env_ids.to(dtype=torch.int32), dtype=wp.int32) if env_ids is not None else None
pos_w, quat_w = self._view.get_world_poses(indices)
self._data.pos_w[env_ids] = pos_w.torch
self._data.quat_w_world[env_ids] = convert_camera_frame_orientation_convention(
quat_w.torch, origin="opengl", target="world"
self._data.pos_w.torch[env_ids] = pos_w.torch

# get_world_poses() returns orientations as a flat 4-float, convert to wp.quatf typed array
quat_w_quatf = wp.array(
ptr=quat_w.warp.ptr, dtype=wp.quatf, shape=(quat_w.warp.shape[0],), device=quat_w.warp.device, copy=False
)
convert_camera_frame_orientation_convention_wp(
src=quat_w_quatf,
dst=self._data.quat_w_world,
origin="opengl",
target="world",
indices=indices,
device=self._device,
)
# notify renderer of updated poses (guarded in case called before initialization completes)
if self._render_data is not None:
Expand Down
Loading
Loading