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:
objectAggregate 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.
- 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).
- 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:
- 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:
- 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.
- Return type:
- 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:
- Return type:
- 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:
- Raises:
ValueError – If obstacle not found in any type.
- Return type:
- enable_obstacle(
- name,
- enabled=True,
- env_idx=0,
Enable or disable an obstacle for collision checking.
- Parameters:
- Raises:
ValueError – If obstacle not found in any type.
- Return type:
- get_obstacle_names(env_idx=0)¶
Get names of all obstacles in an environment.
- check_obstacle_exists(
- name,
- env_idx=0,
Check if an obstacle exists in the scene.
- clear(env_idx=None)¶
Clear all obstacles from one or all environments.
- load_from_scene_cfg(
- scene_cfg,
- env_idx=0,
- store_reference=True,
Load obstacles from a scene configuration into existing storage.
- get_active_types()¶
Get a dictionary of active obstacle types.
- Return type:
- Returns:
Dict with keys ‘cuboid’, ‘mesh’, ‘voxel’ and boolean values.
- to_warp(mesh_max_dist=None)¶
Convert to Warp struct for kernel launches.
- __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:
objectBase class for all obstacles.
- Parameters:
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
MeshandPointCloudobstacles.
- 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:
- Raises:
NotImplementedError – requires implementation in derived class.
- Returns:
instance of obstacle as a trimesh.
- Return type:
- save_as_mesh(
- file_path,
- transform_with_pose=False,
Save obstacle as a mesh file.
- get_cuboid()¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_mesh(process=True)¶
Get obstacle as a 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.
- 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.Nonefor 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:
- Returns:
List of
Sphereinstances.
- __init__(
- name,
- pose=None,
- scale=None,
- color=None,
- texture_id=None,
- texture=None,
- material=<factory>,
- device_cfg=<factory>,
- 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.ObstacleRepresent obstacle as a cuboid.
- Parameters:
- get_trimesh_mesh(
- process=True,
- process_color=True,
- transform_with_pose=False,
Create a trimesh instance from the obstacle representation.
- Parameters:
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- __init__(
- name,
- pose=None,
- scale=None,
- color=None,
- texture_id=None,
- texture=None,
- material=<factory>,
- device_cfg=<factory>,
- dims=<factory>,
- 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.ObstacleObstacle represented as a sphere.
- Parameters:
- get_trimesh_mesh(
- process=True,
- process_color=True,
- transform_with_pose=False,
Create a trimesh instance from the obstacle representation.
- Parameters:
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_cuboid()¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- __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.ObstacleRepresent obstacle as a capsule.
- Parameters:
- get_trimesh_mesh(
- process=True,
- process_color=True,
- transform_with_pose=False,
Create a trimesh instance from the obstacle representation.
- Parameters:
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- __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.ObstacleObstacle represented as a cylinder.
- Parameters:
- get_trimesh_mesh(
- process=True,
- process_color=True,
- transform_with_pose=False,
Create a trimesh instance from the obstacle representation.
- Parameters:
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- __init__(
- name,
- pose=None,
- scale=None,
- color=None,
- texture_id=None,
- texture=None,
- material=<factory>,
- device_cfg=<factory>,
- radius=0.0,
- height=0.0,
- 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.ObstacleObstacle represented as mesh.
- Parameters:
- vertex_colors: List[List[float]] | None = None¶
Vertex colors of mesh. Should be float in range of [0, 1].
- 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:
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- 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.
- 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:
- Returns:
Mesh created from pointcloud.
- Return type:
- __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,
- 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.ObstacleVoxelGrid representation of an obstacle. Requires voxel to contain ESDF.
- Parameters:
name (str)
texture_id (str | None)
texture (str | None)
material (curobo._src.geom.types.Material)
device_cfg (curobo._src.types.device_cfg.DeviceCfg)
voxel_size (float)
feature_tensor (torch.Tensor | None)
xyzr_tensor (torch.Tensor | None)
feature_dtype (torch.dtype)
- 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.
- 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:
- Returns:
XYZR tensor of voxel grid with r referring to voxel size.
- Return type:
- get_occupied_voxels(
- feature_threshold=None,
Get occupied voxels from voxel grid.
- __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:
name (str)
texture_id (str | None)
texture (str | None)
material (curobo._src.geom.types.Material)
device_cfg (curobo._src.types.device_cfg.DeviceCfg)
voxel_size (float)
feature_tensor (torch.Tensor | None)
xyzr_tensor (torch.Tensor | None)
feature_dtype (torch.dtype)
- Return type:
None