newton.sensors.SensorTiledCamera#

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

Bases: object

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

Renders color and depth images for multiple cameras and worlds, organizing the output as tiles in a grid layout.

Parameters:
  • model (Model) – The Newton Model containing shapes to render.

  • options (Options | None) – Render Options.

class Options(checkerboard_texture: 'bool' = False, default_light: 'bool' = False, default_light_shadows: 'bool' = False, colors_per_world: 'bool' = False, colors_per_shape: 'bool' = False, backface_culling: 'bool' = True)#

Bases: object

__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#
checkerboard_texture: bool = False#
colors_per_shape: bool = False#
colors_per_world: bool = False#
default_light: bool = False#
default_light_shadows: bool = False#
class RenderLightType(value)#

Bases: IntEnum

Light types supported by the Warp raytracer.

DIRECTIONAL = 1#

Directional Light.

SPOTLIGHT = 0#

Spotlight.

class RenderOrder(value)#

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

class RenderShapeType(value)#

Bases: IntEnum

Geometry types supported by the Warp raytracer (subset of newton.GeoType).

BOX = 6#
CAPSULE = 3#
CONE = 9#
CYLINDER = 5#
ELLIPSOID = 4#
MESH = 7#
NONE = 11#
PLANE = 0#
SPHERE = 2#
__init__(model, options=None)#
assign_checkerboard_material_to_all_shapes(resolution=64, checker_size=32)#

Assign a 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 all shapes.

Parameters:

seed (int) – The seed to use for the randomizer.

assign_random_colors_per_world(seed=100)#

Assign a random color to all shapes, per world.

Parameters:

seed (int) – The seed to use for the randomizer.

compute_pinhole_camera_rays(width, height, camera_fovs)#

Compute camera-space ray directions for pinhole cameras.

Generates rays in camera space (origin at [0,0,0], direction normalized) for each pixel in each camera based on the specified field-of-view angles.

Parameters:
  • width (int) – Width of the image these rays are computed for.

  • height (int) – Height of the image these rays are computed for.

  • camera_fovs (float | list[float] | np.ndarray | wp.array(dtype=wp.float32)) – Array of vertical FOV angles in radians, shape (num_cameras,).

Returns:

Array of camera rays in camera space, shape (num_cameras, height, width, 2).

Return type:

camera_rays

create_albedo_image_output(width, height, num_cameras=1)#

Create a Warp array for albedo image output.

Parameters:
  • width (int) – Image width.

  • height (int) – Image height.

  • num_cameras (int) – Number of cameras.

Returns:

wp.array of shape (num_worlds, num_cameras, height, width) with dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

create_color_image_output(width, height, num_cameras=1)#

Create a Warp array for color image output.

Parameters:
  • width (int) – Image width.

  • height (int) – Image height.

  • num_cameras (int) – Number of cameras.

Returns:

wp.array of shape (num_worlds, num_cameras, height, width) with dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

create_default_light(enable_shadows=True)#

Create a default directional light for the scene.

Sets up a single directional light oriented at (-1, 1, -1) with shadow casting enabled.

create_depth_image_output(width, height, num_cameras=1)#

Create a Warp array for depth image output.

Parameters:
  • width (int) – Image width.

  • height (int) – Image height.

  • num_cameras (int) – Number of cameras.

Returns:

wp.array of shape (num_worlds, num_cameras, height, width) with dtype float32.

Return type:

array(ndim=4, dtype=float32)

create_normal_image_output(width, height, num_cameras=1)#

Create a Warp array for normal image output.

Parameters:
  • width (int) – Image width.

  • height (int) – Image height.

  • num_cameras (int) – Number of cameras.

Returns:

wp.array of shape (num_worlds, num_cameras, height, width) with dtype vec3f.

Return type:

array(ndim=4, dtype=vec3f)

create_shape_index_image_output(width, height, num_cameras=1)#

Create a Warp array for shape index image output.

Parameters:
  • width (int) – Image width.

  • height (int) – Image height.

  • num_cameras (int) – Number of cameras.

Returns:

wp.array of shape (num_worlds, num_cameras, height, width) with dtype uint32.

Return type:

array(ndim=4, dtype=uint32)

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

Flatten rendered color image to a tiled image buffer.

Arranges (num_worlds x num_cameras) tiles in a grid layout. Each tile shows one camera’s view of one world.

Parameters:
  • image (wp.array(dtype=wp.uint32, ndim=4)) – Color output array from render(), shape (num_worlds, num_cameras, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Optional output array

  • num_worlds_per_row (int | None) – Optional number of rows

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

Flatten rendered depth image to a tiled grayscale image buffer.

Arranges (num_worlds x num_cameras) tiles in a grid. Depth values are inverted (closer = brighter) and normalized to [50, 255] range. Background (depth < 0 or no hit) remains black.

Parameters:
  • image (wp.array(dtype=wp.float32, ndim=4)) – Depth output array from render(), shape (num_worlds, num_cameras, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Optional output array

  • num_worlds_per_row (int | None) – Optional number of rows

  • depth_range (wp.array(dtype=wp.float32) | None) – Depth range to normalize to, shape (2) [near, far], will be automatically determined if None

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

Flatten rendered normal image to a tiled image buffer.

Arranges (num_worlds x num_cameras) tiles in a grid layout. Each tile shows one camera’s view of one world.

Parameters:
  • image (wp.array(dtype=wp.vec3f, ndim=4)) – Normal output array from render(), shape (num_worlds, num_cameras, height, width).

  • out_buffer (wp.array(dtype=wp.uint8, ndim=3) | None) – Optional output array

  • num_worlds_per_row (int | None) – Optional number of rows

render(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. The shape of the output images is (num_worlds, num_cameras, height, width) where element [world_id, camera_id, y, x] is the output generated by the ray in camera_rays[camera_id, y, x].

Parameters:
  • state (State | None) – The current simulation state containing body transforms.

  • camera_transforms (wp.array(dtype=wp.transformf, ndim=2)) – Array of camera transforms in world space, shape (num_cameras, num_worlds).

  • camera_rays (wp.array(dtype=wp.vec3f, ndim=4)) – Array of camera rays in camera space, shape (num_cameras, height, width, 2).

  • color_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Optional output array for color data (num_worlds, num_cameras, height, width). If None, no color rendering is performed.

  • depth_image (wp.array(dtype=wp.float32, ndim=4) | None) – Optional output array for depth data (num_worlds, num_cameras, height, width). If None, no depth rendering is performed.

  • shape_index_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Optional output array for shape index data (num_worlds, num_cameras, height, width). If None, no shape index rendering is performed.

  • normal_image (wp.array(dtype=wp.vec3f, ndim=4) | None) – Optional output array for normal data (num_worlds, num_cameras, height, width). If None, no normal rendering is performed.

  • albedo_image (wp.array(dtype=wp.uint32, ndim=4) | None) – Optional output array for albedo data (num_worlds, num_cameras, height, width). If None, no albedo rendering is performed.

  • refit_bvh (bool) – Whether to refit the BVH or not.

  • clear_data (ClearData | None) – The data to clear the image buffers with (or skip if None).

update_from_state(state)#

Update data from Newton State.

Parameters:

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