curobo.geom.sphere_fit module

class curobo.geom.sphere_fit.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

curobo.geom.sphere_fit.sample_even_fit_mesh(mesh, n_spheres, sphere_radius)
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • sphere_radius (float) –

curobo.geom.sphere_fit.get_voxel_pitch(mesh, n_cubes)
Parameters:
  • mesh (Trimesh) –

  • n_cubes (int) –

curobo.geom.sphere_fit.voxel_fit_surface_mesh(mesh, n_spheres, sphere_radius, voxelize_method='ray')
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • sphere_radius (float) –

  • voxelize_method (str) –

curobo.geom.sphere_fit.get_voxelgrid_from_mesh(mesh, n_spheres, voxelize_method='ray')
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • voxelize_method (str) –

curobo.geom.sphere_fit.voxel_fit_mesh(mesh, n_spheres, surface_sphere_radius, voxelize_method='ray')
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • surface_sphere_radius (float) –

  • voxelize_method (str) –

curobo.geom.sphere_fit.voxel_fit_volume_sample_surface_mesh(mesh, n_spheres, surface_sphere_radius, voxelize_method='ray')
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • surface_sphere_radius (float) –

  • voxelize_method (str) –

curobo.geom.sphere_fit.voxel_fit_volume_inside_mesh(mesh, n_spheres, voxelize_method='ray')
Parameters:
  • mesh (Trimesh) –

  • n_spheres (int) –

  • voxelize_method (str) –

curobo.geom.sphere_fit.fit_spheres_to_mesh(mesh, n_spheres, surface_sphere_radius=0.01, fit_type=SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE, voxelize_method='ray')

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

Parameters:
  • mesh (Trimesh) – Input trimesh

  • n_spheres (int) – _description_

  • surface_sphere_radius (float) – _description_. Defaults to 0.01.

  • fit_type (SphereFitType) – _description_. Defaults to SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE.

  • voxelize_method (str) – _description_. Defaults to “ray”.

Returns:

_description_

Return type:

Tuple[ndarray, List[float]]