newton.sensors.SensorTiledCamera#

class newton.sensors.SensorTiledCamera(model, *, config=None)[source]#

Bases: object

Warp-based tiled camera sensor for raytraced rendering across multiple worlds.

Renders up to five image channels per (world, camera) pair:

  • color – RGBA shaded image (uint32).

  • depth – ray-hit distance [m] (float32); negative means no hit.

  • normal – surface normal at hit point (vec3f).

  • albedo – unshaded surface color (uint32).

  • shape_index – shape id per pixel (uint32).

All output arrays have shape (world_count, camera_count, height, width). Use the flatten_* helpers to rearrange them into tiled RGBA buffers for display, with one tile per (world, camera) pair laid out in a grid.

Shapes without the VISIBLE flag are excluded.

Example

sensor = SensorTiledCamera(model)
rays = sensor.compute_pinhole_camera_rays(width, height, fov)
color = sensor.create_color_image_output(width, height)

# each step
sensor.update(state, camera_transforms, rays, color_image=color)

See Config for optional rendering settings and ClearData / DEFAULT_CLEAR_DATA / GRAY_CLEAR_DATA for image-clear presets.

class Config(checkerboard_texture=False, default_light=False, default_light_shadows=False, colors_per_world=False, colors_per_shape=False, backface_culling=True)#

Bases: object

Rendering configuration.

__init__(checkerboard_texture=False, default_light=False, default_light_shadows=False, colors_per_world=False, colors_per_shape=False, backface_culling=True)#
backface_culling: bool = True#

Cull back-facing triangles.

checkerboard_texture: bool = False#

Apply a checkerboard texture to all shapes.

colors_per_shape: bool = False#

Assign a random color per shape (ignored when colors_per_world is True).

colors_per_world: bool = False#

Assign a random color palette per world.

default_light: bool = False#

Add a default directional light to the scene.

default_light_shadows: bool = False#

Enable shadows for the default light (requires default_light).

class RenderLightType(*values)#

Bases: IntEnum

Light types supported by the Warp raytracer.

DIRECTIONAL = 1#

Directional Light.

SPOTLIGHT = 0#

Spotlight.

class RenderOrder(*values)#

Bases: IntEnum

Render Order

PIXEL_PRIORITY = 0#

Render the same pixel of every view before continuing to the next one

TILED = 2#

Render pixels in tiles, defined by tile_width x tile_height

VIEW_PRIORITY = 1#

Render all pixels of a whole view before continuing to the next one

__init__(model, *, config=None)#
assign_checkerboard_material_to_all_shapes(resolution=64, checker_size=32)#

Assign a gray checkerboard texture material to all shapes. Creates a gray checkerboard pattern texture and applies it to all shapes in the scene.

Parameters:
  • resolution (int) – Texture resolution in pixels (square texture).

  • checker_size (int) – Size of each checkerboard square in pixels.

assign_random_colors_per_shape(seed=100)#

Assign a random color to each shape.

Parameters:

seed (int) – Random seed.

assign_random_colors_per_world(seed=100)#

Assign each world a random color, applied to all its shapes.

Parameters:

seed (int) – Random seed.

compute_pinhole_camera_rays(width, height, camera_fovs)#

Compute camera-space ray directions for pinhole cameras.

Generates rays in camera space (origin at the camera center, direction normalized) for each pixel based on the vertical field of view.

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_fovs (float | list[float] | np.ndarray | wp.array(dtype=wp.float32)) – Vertical FOV angles [rad], shape (camera_count,).

Returns:

Shape (camera_count, height, width, 2), dtype vec3f.

Return type:

camera_rays

create_albedo_image_output(width, height, camera_count=1)#

Create an albedo output array for update().

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_count (int) – Number of cameras.

Returns:

Array of shape (world_count, camera_count, height, width), dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

create_color_image_output(width, height, camera_count=1)#

Create a color output array for update().

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_count (int) – Number of cameras.

Returns:

Array of shape (world_count, camera_count, height, width), dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

create_default_light(enable_shadows=True)#

Create a default directional light oriented at (-1, 1, -1).

Parameters:

enable_shadows (bool) – Enable shadow casting for this light.

create_depth_image_output(width, height, camera_count=1)#

Create a depth output array for update().

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_count (int) – Number of cameras.

Returns:

Array of shape (world_count, camera_count, height, width), dtype float32.

Return type:

array(ndim=4, dtype=float32)

create_normal_image_output(width, height, camera_count=1)#

Create a normal output array for update().

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_count (int) – Number of cameras.

Returns:

Array of shape (world_count, camera_count, height, width), dtype vec3f.

Return type:

array(ndim=4, dtype=vec3f)

create_shape_index_image_output(width, height, camera_count=1)#

Create a shape-index output array for update().

Parameters:
  • width (int) – Image width [px].

  • height (int) – Image height [px].

  • camera_count (int) – Number of cameras.

Returns:

Array of shape (world_count, camera_count, height, width), dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

flatten_color_image_to_rgba(image, out_buffer=None, worlds_per_row=None)#

Flatten rendered color image to a tiled RGBA buffer.

Arranges (world_count * camera_count) tiles in a grid. Each tile shows one camera’s view of one world.

Parameters:
  • image (wp.array(dtype=wp.uint32, ndim=4)) – Color output from update(), shape (world_count, camera_count, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Pre-allocated RGBA buffer. If None, allocates a new one.

  • worlds_per_row (int | None) – Tiles per row in the grid. If None, picks a square-ish layout.

flatten_depth_image_to_rgba(image, out_buffer=None, worlds_per_row=None, depth_range=None)#

Flatten rendered depth image to a tiled RGBA buffer.

Encodes depth as grayscale: inverts values (closer = brighter) and normalizes to the [50, 255] range. Background pixels (no hit) remain black.

Parameters:
  • image (wp.array(dtype=wp.float32, ndim=4)) – Depth output from update(), shape (world_count, camera_count, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Pre-allocated RGBA buffer. If None, allocates a new one.

  • worlds_per_row (int | None) – Tiles per row in the grid. If None, picks a square-ish layout.

  • depth_range (wp.array(dtype=wp.float32) | None) – Depth range to normalize to, shape (2,) [near, far]. If None, computes from image.

flatten_normal_image_to_rgba(image, out_buffer=None, worlds_per_row=None)#

Flatten rendered normal image to a tiled RGBA buffer.

Arranges (world_count * camera_count) tiles in a grid. Each tile shows one camera’s view of one world.

Parameters:
  • image (wp.array(dtype=wp.vec3f, ndim=4)) – Normal output from update(), shape (world_count, camera_count, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Pre-allocated RGBA buffer. If None, allocates a new one.

  • worlds_per_row (int | None) – Tiles per row in the grid. If None, picks a square-ish layout.

sync_transforms(state)#

Synchronize shape transforms from the simulation state.

update() calls this automatically when state is not None.

Parameters:

state (State) – The current simulation state containing body transforms.

update(state, camera_transforms, camera_rays, *, color_image=None, depth_image=None, shape_index_image=None, normal_image=None, albedo_image=None, refit_bvh=True, clear_data=DEFAULT_CLEAR_DATA)#

Render output images for all worlds and cameras.

Each output array has shape (world_count, camera_count, height, width) where element [world_id, camera_id, y, x] corresponds to the ray in camera_rays[camera_id, y, x]. Each output channel is optional – pass None to skip that channel’s rendering entirely.

Parameters:
  • state (State | None) – Simulation state with body transforms. If not None, calls sync_transforms() first.

  • camera_transforms (wp.array(dtype=wp.transformf, ndim=2)) – Camera-to-world transforms, shape (camera_count, world_count).

  • camera_rays (wp.array(dtype=wp.vec3f, ndim=4)) – Camera-space rays from compute_pinhole_camera_rays(), shape (camera_count, height, width, 2).

  • color_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Output for RGBA color. None to skip.

  • depth_image (wp.array(dtype=wp.float32, ndim=4) | None) – Output for ray-hit distance [m]. None to skip.

  • shape_index_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Output for per-pixel shape id. None to skip.

  • normal_image (wp.array(dtype=wp.vec3f, ndim=4) | None) – Output for surface normals. None to skip.

  • albedo_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Output for unshaded surface color. None to skip.

  • refit_bvh (bool) – Refit the BVH before rendering.

  • clear_data (ClearData | None) – Values to clear output buffers with. None to skip clearing. See DEFAULT_CLEAR_DATA, GRAY_CLEAR_DATA.