curobo.geom.sphere_fit module

Approximate mesh geometry with spheres.

class SphereFitType(value)

Bases: Enum

Supported sphere fit types are listed here. VOXEL_VOLUME_SAMPLE_SURFACE works best.

See Geometry Approximation to Spheres for more details.

SAMPLE_SURFACE = 'sample_surface'

samples the surface of the mesh to approximate geometry

VOXEL_SURFACE = 'voxel_surface'

voxelizes the volume and returns voxel positions that are intersecting with surface.

VOXEL_VOLUME = 'voxel_volume'

voxelizes the volume and returns all ocupioed voxel positions.

VOXEL_VOLUME_INSIDE = 'voxel_volume_inside'

voxelizes the volume and returns voxel positions that are inside the surface of the geometry

VOXEL_VOLUME_SAMPLE_SURFACE = 'voxel_volume_sample_surface'

voxelizes the volume and returns voxel positions that are inside the surface, along with surface sampled positions

sample_even_fit_mesh(
mesh: Trimesh,
n_spheres: int,
sphere_radius: float,
) Tuple[array, List[float]]

Sample even points on the surface of the mesh and return them with the given radius.

Parameters:
  • mesh – Mesh to sample points from.

  • n_spheres – Number of spheres to sample.

  • sphere_radius – Sphere radius.

Returns:

Tuple of points and radius.

get_voxel_pitch(
mesh: Trimesh,
n_cubes: int,
) float

Get the pitch of the voxel grid based on the mesh and number of cubes.

Parameters:
  • mesh – Mesh to get the pitch from.

  • n_cubes – Number of voxels to fit.

Returns:

Pitch of the voxel grid.

Return type:

float

voxel_fit_surface_mesh(
mesh: Trimesh,
n_spheres: int,
sphere_radius: float,
voxelize_method: str = 'ray',
) Tuple[array, List[float]]

Get voxel grid from mesh and fit spheres to the surface.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of spheres to fit.

  • sphere_radius – Radius of the spheres.

  • voxelize_method – TriMesh Voxelization method. Defaults to “ray”.

Returns:

Tuple of sphere positions and sphere radius.

get_voxelgrid_from_mesh(
mesh: Trimesh,
n_spheres: int,
voxelize_method: str = 'ray',
) Tuple[array | None, array | None]

Get voxel grid from mesh using trimesh.voxel.creation.voxelize.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of voxels to fit.

  • voxelize_method – Voxelize method. Defaults to “ray”.

Returns:

Tuple of occupied voxels and side of voxels (length of cube). Returns [None, None] if

voxelization fails.

voxel_fit_mesh(
mesh: Trimesh,
n_spheres: int,
surface_sphere_radius: float,
voxelize_method: str = 'ray',
) Tuple[array, List[float]]

Voxelize mesh, fit spheres to volume and near surface. Return the fitted spheres.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of spheres to fit.

  • surface_sphere_radius – Radius of the spheres on the surface. This radius will be added to points on the surface of the mesh, causing the spheres to inflate the mesh volume by this amount.

  • voxelize_method – Voxelization method to use, select from trimesh.voxel.creation.voxelize.

Returns:

Tuple of sphere positions and their radius.

voxel_fit_volume_inside_mesh(
mesh: Trimesh,
n_spheres: int,
voxelize_method: str = 'ray',
) Tuple[ndarray, array]

Voxelize mesh, fit spheres to volume. Return the fitted spheres.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of spheres to fit.

  • voxelize_method – Voxelization method to use, select from trimesh.voxel.creation.voxelize.

Returns:

Tuple of sphere positions and their radius.

voxel_fit_volume_sample_surface_mesh(
mesh: Trimesh,
n_spheres: int,
surface_sphere_radius: float,
voxelize_method: str = 'ray',
) Tuple[ndarray, array]

Voxelize mesh, fit spheres to volume, and sample surface for points.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of spheres to fit.

  • surface_sphere_radius – Radius of the spheres on the surface. This radius will be added to points on the surface of the mesh, causing the spheres to inflate the mesh volume by this amount.

  • voxelize_method – Voxelization method to use, select from trimesh.voxel.creation.voxelize.

Returns:

Tuple of sphere positions and their radius.

fit_spheres_to_mesh(
mesh: Trimesh,
n_spheres: int,
surface_sphere_radius: float = 0.01,
fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
voxelize_method: str = 'ray',
) Tuple[ndarray, array]

Approximate a mesh with spheres. See Geometry Approximation to Spheres for more details.

Parameters:
  • mesh – Input mesh.

  • n_spheres – Number of spheres to fit.

  • surface_sphere_radius – Radius of the spheres on the surface. This radius will be added to points on the surface of the mesh, causing the spheres to inflate the mesh volume by this amount.

  • fit_type – Sphere fit type, select from SphereFitType.

  • voxelize_method – Voxelization method to use, select from trimesh.voxel.creation.voxelize.

Returns:

Tuple of spehre positions and their radius.