curobo.scene module

Scene representation module.

This module provides classes for building and managing scene representations with various obstacle types.

Example

```python from curobo.scene import Scene, Cuboid, Mesh, Sphere

# Build scene programmatically scene = Scene(

cuboid=[

Cuboid(name=”table”, dims=[1.0, 1.0, 0.1], pose=[0, 0, 0.5, 1, 0, 0, 0]), Cuboid(name=”wall”, dims=[0.1, 2.0, 2.0], pose=[1.0, 0, 1.0, 1, 0, 0, 0]),

], sphere=[

Sphere(name=”ball”, radius=0.1, pose=[0.5, 0.5, 1.0, 1, 0, 0, 0])

], mesh=[

Mesh(name=”object”, file_path=”model.obj”, pose=[0, 0, 0.6, 1, 0, 0, 0])

]

)

# Or load from file/dict scene = Scene.create(scene_dict)

# Modify scene scene.add_obstacle(Sphere(name=”new_ball”, radius=0.2, pose=[…])) scene.remove_obstacle(“old_ball”) ```

Scene

alias of curobo._src.geom.types.SceneCfg

class SceneData(
cuboids=None,
meshes=None,
voxels=None,
num_envs=1,
device_cfg=<factory>,
scene_model=None,
)

Bases: object

Aggregate GPU tensor storage for all scene obstacle types.

This dataclass holds references to individual data storage for each obstacle type (cuboids, meshes, voxels). It provides a unified interface for managing scene obstacles while delegating to the appropriate type-specific storage.

Use this as the primary container for scene data. It can be passed to collision checkers, TSDF integrators, or visualizers.

Example

>>> scene = SceneData.from_scene_cfg(scene_cfg, device_cfg)
>>> scene.add_obstacle(Cuboid(name="box", pose=[0,0,0,1,0,0,0], dims=[0.1,0.1,0.1]))
>>> scene.update_obstacle_pose("box", new_pose)
Parameters:
  • cuboids (curobo._src.geom.data.data_cuboid.CuboidData | None)

  • meshes (curobo._src.geom.data.data_mesh.MeshData | None)

  • voxels (curobo._src.geom.data.data_voxel.VoxelData | None)

  • num_envs (int)

  • device_cfg (curobo._src.types.device_cfg.DeviceCfg)

  • scene_model (curobo._src.geom.types.SceneCfg | List[curobo._src.geom.types.SceneCfg] | None)

cuboids: curobo._src.geom.data.data_cuboid.CuboidData | None = None

Cuboid (OBB) tensor storage. None if no cuboids configured.

meshes: curobo._src.geom.data.data_mesh.MeshData | None = None

Mesh tensor storage with Warp BVH. None if no meshes configured.

voxels: curobo._src.geom.data.data_voxel.VoxelData | None = None

Voxel grid (ESDF) tensor storage. None if no voxels configured.

num_envs: int = 1

Number of parallel environments.

device_cfg: curobo._src.types.device_cfg.DeviceCfg

Device configuration for tensor creation.

scene_model: curobo._src.geom.types.SceneCfg | List[curobo._src.geom.types.SceneCfg] | None = None

CPU reference to scene configuration (for reference updates).

get_valid_data()
Return type:

List[Union[CuboidData, MeshData, VoxelData]]

classmethod create_cache(
num_envs,
device_cfg,
cuboid_cache=None,
mesh_cache=None,
mesh_max_dist=0.1,
voxel_cache=None,
)

Create an empty cache for scene obstacles.

Parameters:
  • num_envs (int) – Number of parallel environments.

  • device_cfg (DeviceCfg) – Device and dtype configuration.

  • cuboid_cache (Optional[int]) – Maximum number of cuboids per environment. None to skip.

  • mesh_cache (Optional[int]) – Maximum number of meshes per environment. None to skip.

  • mesh_max_dist (float) – Maximum query distance for mesh SDF.

  • voxel_cache (Optional[dict]) – Voxel cache configuration dict with keys: - layers: Maximum number of voxel grids - dims: Grid dimensions [x, y, z] in meters - voxel_size: Size of each voxel in meters

Return type:

SceneData

Returns:

Empty SceneData with allocated GPU buffers.

classmethod from_scene_cfg(
scene_cfg,
device_cfg,
num_envs=1,
env_idx=0,
cuboid_cache=None,
mesh_cache=None,
mesh_max_dist=0.1,
voxel_cache=None,
)

Create SceneData from a scene configuration.

Parameters:
  • scene_cfg (SceneCfg) – Scene configuration containing obstacles.

  • device_cfg (DeviceCfg) – Device and dtype configuration.

  • num_envs (int) – Number of parallel environments.

  • env_idx (int) – Environment index to load the obstacles into.

  • cuboid_cache (Optional[int]) – Max cuboids. If None, uses len(scene_cfg.cuboid).

  • mesh_cache (Optional[int]) – Max meshes. If None, uses len(scene_cfg.mesh).

  • mesh_max_dist (float) – Maximum query distance for mesh SDF.

  • voxel_cache (Optional[dict]) – Voxel cache config. If None, derives from scene_cfg.voxel.

Return type:

SceneData

Returns:

SceneData populated with obstacles from the scene config.

classmethod from_batch_scene_cfg(
scene_cfg_list,
device_cfg,
cuboid_cache=None,
mesh_cache=None,
mesh_max_dist=0.1,
voxel_cache=None,
)

Create SceneData from a list of scene configurations.

Each scene config is loaded into a separate environment.

Parameters:
  • scene_cfg_list (List[SceneCfg]) – List of scene configurations, one per environment.

  • device_cfg (DeviceCfg) – Device and dtype configuration.

  • cuboid_cache (Optional[int]) – Max cuboids per env. If None, uses max across scenes.

  • mesh_cache (Optional[int]) – Max meshes per env. If None, uses max across scenes.

  • mesh_max_dist (float) – Maximum query distance for mesh SDF.

  • voxel_cache (Optional[dict]) – Voxel cache config.

Return type:

SceneData

Returns:

SceneData populated with obstacles from all scene configs.

add_obstacle(
obstacle,
env_idx=0,
)

Add an obstacle to the scene.

Automatically routes to the appropriate storage based on obstacle type.

Parameters:
  • obstacle (Obstacle) – Obstacle to add (Cuboid, Mesh, or VoxelGrid).

  • env_idx (int) – Environment index to add to.

Return type:

int

Returns:

Index of the added obstacle within its type.

Raises:

ValueError – If obstacle type is not supported or cache not initialized.

update_obstacle_pose(
name,
pose,
env_idx=0,
)

Update the pose of an existing obstacle by name.

Searches across all obstacle types to find the obstacle.

Parameters:
  • name (str) – Name of the obstacle to update.

  • pose (Pose) – New pose in world frame.

  • env_idx (int) – Environment index.

Raises:

ValueError – If obstacle not found in any type.

Return type:

None

enable_obstacle(
name,
enabled=True,
env_idx=0,
)

Enable or disable an obstacle for collision checking.

Parameters:
  • name (str) – Name of the obstacle.

  • enabled (bool) – True to enable, False to disable.

  • env_idx (int) – Environment index.

Raises:

ValueError – If obstacle not found in any type.

Return type:

None

get_obstacle_names(env_idx=0)

Get names of all obstacles in an environment.

Parameters:

env_idx (int) – Environment index.

Return type:

List[str]

Returns:

List of obstacle names across all types.

check_obstacle_exists(
name,
env_idx=0,
)

Check if an obstacle exists in the scene.

Return type:

bool

Parameters:
clear(env_idx=None)

Clear all obstacles from one or all environments.

Parameters:

env_idx (Optional[int]) – Environment to clear. If None, clears all environments.

Return type:

None

load_from_scene_cfg(
scene_cfg,
env_idx=0,
store_reference=True,
)

Load obstacles from a scene configuration into existing storage.

Parameters:
  • scene_cfg (SceneCfg) – Scene configuration containing obstacles to load.

  • env_idx (int) – Environment index to load obstacles into.

  • store_reference (bool) – If True, stores scene_cfg in scene_model.

Return type:

None

has_cuboids()

Check if cuboid data is available.

Return type:

bool

has_meshes()

Check if mesh data is available.

Return type:

bool

has_voxels()

Check if voxel data is available.

Return type:

bool

get_active_types()

Get a dictionary of active obstacle types.

Return type:

dict

Returns:

Dict with keys ‘cuboid’, ‘mesh’, ‘voxel’ and boolean values.

to_warp(mesh_max_dist=None)

Convert to Warp struct for kernel launches.

Parameters:

mesh_max_dist (Optional[float]) – Override max query distance for meshes.

Return type:

SceneDataWarp

Returns:

SceneDataWarp struct for use in Warp kernels.

__init__(
cuboids=None,
meshes=None,
voxels=None,
num_envs=1,
device_cfg=<factory>,
scene_model=None,
)
Parameters:
  • cuboids (curobo._src.geom.data.data_cuboid.CuboidData | None)

  • meshes (curobo._src.geom.data.data_mesh.MeshData | None)

  • voxels (curobo._src.geom.data.data_voxel.VoxelData | None)

  • num_envs (int)

  • device_cfg (curobo._src.types.device_cfg.DeviceCfg)

  • scene_model (curobo._src.geom.types.SceneCfg | List[curobo._src.geom.types.SceneCfg] | None)

Return type:

None

class Obstacle(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
)

Bases: object

Base class for all obstacles.

Parameters:
name: str

Unique name of obstacle.

pose: List[float] | None = None

Pose of obstacle as a list with format [x y z qw qx qy qz]

scale: List[float] | None = None

Scale obsctacle. This is only implemented for Mesh and PointCloud obstacles.

color: List[float] | None = None

Color of obstacle to use in visualization.

texture_id: str | None = None

Texture name for the obstacle.

texture: str | None = None

Texture to apply to obstacle in visualization.

material: curobo._src.geom.types.Material

Material properties to apply in visualization.

device_cfg: curobo._src.types.device_cfg.DeviceCfg

Device and floating point precision to use for tensors.

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool, optional) – process when loading from file. Defaults to True.

  • process_color (bool)

  • transform_with_pose (bool)

Raises:

NotImplementedError – requires implementation in derived class.

Returns:

instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

save_as_mesh(
file_path,
transform_with_pose=False,
)

Save obstacle as a mesh file.

Parameters:
  • file_path (str) – Path to save mesh file.

  • transform_with_pose (bool) – Transform obstacle with pose before saving.

get_cuboid()

Get oriented bounding box of obstacle (OBB).

Returns:

returns obstacle as a cuboid.

Return type:

Cuboid

get_mesh(process=True)

Get obstacle as a mesh.

Parameters:

process (bool, optional) – process mesh from file. Defaults to True.

Returns:

obstacle as a mesh.

Return type:

Mesh

get_transform_matrix()

Get homogenous transformation matrix from pose.

Returns:

transformation matrix.

Return type:

np.ndarray

get_sphere(n=1)

Compute a sphere that fits in the volume of the object.

Parameters:

n (int) – number of spheres

Return type:

Sphere

Returns:

spheres

get_bounding_spheres(
num_spheres=None,
surface_radius=0.002,
fit_type=SphereFitType.MORPHIT,
pre_transform_pose=None,
device_cfg=DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
)

Compute spheres that approximate the volume of the object.

Parameters:
  • num_spheres (Optional[int]) – Number of spheres. None for automatic.

  • surface_radius (float) – Radius added to surface-sampled spheres.

  • fit_type (SphereFitType) – Sphere fit algorithm.

  • pre_transform_pose (Optional[Pose]) – Optional pose applied before the object pose.

  • device_cfg (DeviceCfg) – Device configuration.

Return type:

List[Sphere]

Returns:

List of Sphere instances.

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
)
Parameters:
Return type:

None

class Cuboid(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
dims=<factory>,
)

Bases: curobo._src.geom.types.Obstacle

Represent obstacle as a cuboid.

Parameters:
dims: List[float]

Dimensions of cuboid in meters [x_length, y_length, z_length].

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool) – Flag is not used.

  • process_color (bool) – Flag is not used.

  • transform_with_pose (bool)

Returns:

Instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
dims=<factory>,
)
Parameters:
Return type:

None

class Sphere(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
position=None,
)

Bases: curobo._src.geom.types.Obstacle

Obstacle represented as a sphere.

Parameters:
radius: float = 0.0

Radius of sphere in meters.

position: List[float] | None = None

Position is deprecated, use pose instead

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool) – Flag is not used.

  • process_color (bool) – Flag is not used.

  • transform_with_pose (bool)

Returns:

Instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

get_cuboid()

Get oriented bounding box of obstacle (OBB).

Returns:

returns obstacle as a cuboid.

Return type:

Cuboid

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
position=None,
)
Parameters:
Return type:

None

class Capsule(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
base=<factory>,
tip=<factory>,
)

Bases: curobo._src.geom.types.Obstacle

Represent obstacle as a capsule.

Parameters:
radius: float = 0.0

Radius of capsule in meters.

base: List[float]

Base of capsule in meters [x, y, z].

tip: List[float]

Tip of capsule in meters [x, y, z].

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool) – Flag is not used.

  • process_color (bool) – Flag is not used.

  • transform_with_pose (bool)

Returns:

Instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
base=<factory>,
tip=<factory>,
)
Parameters:
Return type:

None

class Cylinder(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
height=0.0,
)

Bases: curobo._src.geom.types.Obstacle

Obstacle represented as a cylinder.

Parameters:
radius: float = 0.0

Radius of cylinder in meters.

height: float = 0.0

Height of cylinder in meters.

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool) – Flag is not used.

  • process_color (bool) – Flag is not used.

  • transform_with_pose (bool)

Returns:

Instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
radius=0.0,
height=0.0,
)
Parameters:
Return type:

None

class Mesh(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
file_path=None,
file_string=None,
urdf_path=None,
vertices=None,
faces=None,
vertex_colors=None,
vertex_normals=None,
face_colors=None,
)

Bases: curobo._src.geom.types.Obstacle

Obstacle represented as mesh.

Parameters:
file_path: str | None = None

Path to mesh file.

file_string: str | None = None

Full mesh as a string, loading from this is not implemented yet.

urdf_path: str | None = None

Path to urdf file, does not support loading from this yet.

vertices: List[List[float]] | None = None

Vertices of mesh.

faces: List[int] | None = None

Faces of mesh.

vertex_colors: List[List[float]] | None = None

Vertex colors of mesh. Should be float in range of [0, 1].

vertex_normals: List[List[float]] | None = None

Vertex normals of mesh.

face_colors: List[List[float]] | None = None

Face colors of mesh. Should be float in range of [0, 1].

get_trimesh_mesh(
process=True,
process_color=True,
transform_with_pose=False,
)

Create a trimesh instance from the obstacle representation.

Parameters:
  • process (bool) – process flag passed to trimesh.load.

  • process_color (bool) – if True, load mesh visual from texture.

  • transform_with_pose (bool)

Returns:

Instance of obstacle as a trimesh.

Return type:

trimesh.Trimesh

to_cpu()

Convert the mesh to CPU memory.

to_gpu()

Convert the mesh to GPU memory.

update_material()

Load material into vertex_colors and face_colors.

get_mesh_data(process=True)

Get vertices and faces of mesh.

Parameters:

process (bool) – process flag passed to trimesh.load.

Returns:

vertices and faces of mesh.

Return type:

Tuple[List[List[float]], List[int]]

static from_pointcloud(
pointcloud,
pitch=0.02,
name='world_pc',
pose=[0, 0, 0, 1, 0, 0, 0],
filter_close_points=0.0,
)

Create a mesh from a pointcloud via voxelized surface extraction.

Voxelizes the point cloud into a 3D grid and emits quad faces on voxel boundaries (occupied vs. empty), producing a watertight mesh without requiring scikit-image or marching cubes.

Parameters:
  • pointcloud (ndarray) – Input pointcloud of shape [n_pts, 3].

  • pitch (float) – Voxel size in meters.

  • name – Name to assign to created mesh.

  • pose (List[float]) – Pose to assign to created mesh.

  • filter_close_points (float) – Filter points closer than this distance to the origin. Threshold is in meters and should be positive.

Returns:

Mesh created from pointcloud.

Return type:

Mesh

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
file_path=None,
file_string=None,
urdf_path=None,
vertices=None,
faces=None,
vertex_colors=None,
vertex_normals=None,
face_colors=None,
)
Parameters:
Return type:

None

class VoxelGrid(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
dims=<factory>,
voxel_size=0.02,
feature_tensor=None,
xyzr_tensor=None,
feature_dtype=torch.float32,
)

Bases: curobo._src.geom.types.Obstacle

VoxelGrid representation of an obstacle. Requires voxel to contain ESDF.

Parameters:
dims: List[float]

Dimensions of voxel grid in meters [x_length, y_length, z_length].

voxel_size: float = 0.02

Voxel size in meters.

feature_tensor: torch.Tensor | None = None

Feature tensor of voxel grid, typically ESDF.

xyzr_tensor: torch.Tensor | None = None

XYZR tensor of voxel grid.

feature_dtype: torch.dtype = torch.float32

Data type of feature tensor.

get_grid_shape()

Get shape of voxel grid.

Return type:

Tuple[List[int], List[float], List[float]]

create_xyzr_tensor(
transform_to_origin=False,
device_cfg=DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
)

Create XYZR tensor of voxel grid.

Parameters:
  • transform_to_origin (bool) – Transform points to origin.

  • device_cfg (DeviceCfg) – Device and floating point precision to use for tensors.

Returns:

XYZR tensor of voxel grid with r referring to voxel size.

Return type:

xyzr_tensor

get_occupied_voxels(
feature_threshold=None,
)

Get occupied voxels from voxel grid.

Parameters:

feature_threshold (Optional[float]) – esdf value threshold to consider as occupied.

Return type:

Tensor

Returns:

occupied voxels as a tensor of shape [occupied_voxels].

clone()

Clone data of voxel grid.

Return type:

VoxelGrid

__init__(
name,
pose=None,
scale=None,
color=None,
texture_id=None,
texture=None,
material=<factory>,
device_cfg=<factory>,
dims=<factory>,
voxel_size=0.02,
feature_tensor=None,
xyzr_tensor=None,
feature_dtype=torch.float32,
)
Parameters:
Return type:

None