curobo.sphere_fit module¶
Sphere fitting utilities for approximating mesh geometry.
cuRobo represents robot links and scene obstacles as collections of spheres for fast GPU collision checking. This module exposes the public API for fitting sphere approximations to triangle meshes and inspecting fit quality.
Typical workflow:
Load a triangle mesh (e.g. with
trimesh).Optionally call
estimate_sphere_countto pick a reasonable sphere count from the mesh bounding volume.Call
fit_spheres_to_meshwith the desiredSphereFitTypestrategy.Inspect the returned
SphereFitResultfor sphere centers, radii, andSphereFitMetricsfit quality.
Example
import trimesh
from curobo.sphere_fit import (
SphereFitType,
estimate_sphere_count,
fit_spheres_to_mesh,
)
mesh = trimesh.load("link.obj")
n = estimate_sphere_count(mesh)
result = fit_spheres_to_mesh(mesh, n_spheres=n, fit_type=SphereFitType.VOXEL)
centers, radii, metrics = result.centers, result.radii, result.metrics
- class SphereFitMetrics(
- num_spheres=0,
- coverage=0.0,
- protrusion=0.0,
- protrusion_dist_mean=0.0,
- protrusion_dist_p95=0.0,
- surface_gap_mean=0.0,
- surface_gap_p95=0.0,
- max_uncovered_gap=0.0,
- volume_ratio=0.0,
Bases:
objectQuality metrics for a sphere fit to a single mesh/link.
All distance fields are in metres. Fractions are in
[0, 1].- Parameters:
- protrusion_dist_mean: float = 0.0¶
Mean distance (m) of protruding sphere-surface points to the mesh.
- surface_gap_p95: float = 0.0¶
95th-percentile gap (m) from mesh surface samples to nearest sphere surface.
- max_uncovered_gap: float = 0.0¶
Maximum gap (m) from mesh surface samples to nearest sphere surface.
- __init__(
- num_spheres=0,
- coverage=0.0,
- protrusion=0.0,
- protrusion_dist_mean=0.0,
- protrusion_dist_p95=0.0,
- surface_gap_mean=0.0,
- surface_gap_p95=0.0,
- max_uncovered_gap=0.0,
- volume_ratio=0.0,
- class SphereFitResult(
- centers,
- radii,
- num_spheres=0,
- metrics=None,
- fit_time_s=None,
- used_mesh=None,
- history=<factory>,
- debug_info=<factory>,
Bases:
objectResult of a sphere fitting operation.
Always contains the fitted sphere geometry (
centers,radii). Quality metrics are populated inmetricsonly whencompute_metrics=Trueis passed tofit_spheres_to_mesh.- Parameters:
centers (torch.Tensor)
radii (torch.Tensor)
num_spheres (int)
metrics (curobo._src.geom.sphere_fit.types.SphereFitMetrics | None)
fit_time_s (float | None)
used_mesh (trimesh.base.Trimesh | None)
history (List[Tuple[numpy.ndarray, numpy.ndarray]])
- __init__(
- centers,
- radii,
- num_spheres=0,
- metrics=None,
- fit_time_s=None,
- used_mesh=None,
- history=<factory>,
- debug_info=<factory>,
- Parameters:
centers (torch.Tensor)
radii (torch.Tensor)
num_spheres (int)
metrics (curobo._src.geom.sphere_fit.types.SphereFitMetrics | None)
fit_time_s (float | None)
used_mesh (trimesh.base.Trimesh | None)
history (List[Tuple[numpy.ndarray, numpy.ndarray]])
- Return type:
None
- centers: torch.Tensor¶
Sphere centre positions, shape
(N, 3), float32, CUDA.
- radii: torch.Tensor¶
Sphere radii, shape
(N,), float32, CUDA.
- metrics: curobo._src.geom.sphere_fit.types.SphereFitMetrics | None = None¶
Quality metrics.
Noneuntilfit_spheres_to_meshis called withcompute_metrics=True.
- used_mesh: trimesh.base.Trimesh | None = None¶
The mesh that was actually used for fitting. May differ from the input when hollow-mesh detection replaces it with its convex hull.
- history: List[Tuple[numpy.ndarray, numpy.ndarray]]¶
Per-iteration snapshots of
(centers, radii)recorded during optimization. Empty for non-iterative methods (SURFACE, VOXEL).
- debug_info: Dict[str, Any] | None¶
Diagnostic metadata from the fitting pipeline. Typical keys:
used_convex_hull(bool): convex hull was substituted for the input.auto_n_spheres(bool): sphere count was determined automatically.requested_n_spheres(int | None): caller’s originalnum_spheres.resolved_n_spheres(int): sphere count actually used.fallback_used(bool): primary method failed, distance-field fallback ran.fit_type(str): theSphereFitTypevalue used.
- class SphereFitType(value)¶
Bases:
enum.EnumSupported sphere fit types.
See Use Cases for more details.
- SURFACE = 'surface'¶
Samples the surface of the mesh evenly, fixed radius. Fast fallback.
- VOXEL = 'voxel'¶
Bbox grid + SDF filtering. Interior voxels with inscribed radii.
- MORPHIT = 'morphit'¶
Voxel-grid seeding + Adam optimization.
- estimate_sphere_count(
- mesh,
- sphere_density=1.0,
Estimate the number of spheres needed to approximate a mesh.
Uses bounding-box volume scaled by a density multiplier, clamped to
[3, 100 * sphere_density]. Both the raw count and the per-link cap scale with sphere_density, sodensity=0.5halves the maximum anddensity=2.0doubles it.
- fit_spheres_to_mesh(
- mesh,
- num_spheres=None,
- sphere_density=1.0,
- surface_radius=0.005,
- fit_type=SphereFitType.MORPHIT,
- iterations=200,
- compute_metrics=False,
- coverage_weight=None,
- protrusion_weight=None,
- clip_plane=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),
Approximate a mesh with spheres.
- Parameters:
mesh (
Trimesh) – Input mesh.num_spheres (
Optional[int]) – Explicit number of spheres to fit. WhenNone(default), estimated automatically using sphere_density.sphere_density (
float) – Dimensionless density multiplier used when num_spheres isNone. Scales both the sphere count estimate and the per-link cap.1.0(default) gives a balanced count;2.0doubles it;0.5halves it. Practical range:0.1–10.0.surface_radius (
float) – Radius added to surface-sampled spheres. Only affects theSURFACEfit type and the surface-sampling fallback.fit_type (
SphereFitType) – Fitting algorithm; seeSphereFitType.iterations (
int) – Optimization iterations (only used byMORPHIT).compute_metrics (
bool) – When True, compute quality metrics (coverage, protrusion, surface gap, volume ratio) on the result.coverage_weight (
Optional[float]) – MorphIt coverage loss weight. Higher values force spheres to fill the mesh volume more completely. Only used byMORPHIT. WhenNone, uses the default (1000.0).protrusion_weight (
Optional[float]) – MorphIt protrusion loss weight. Higher values penalise sphere surface area outside the mesh more aggressively. Only used byMORPHIT. WhenNone, uses the default (10.0).clip_plane (
Optional[tuple]) – Half-plane constraint((nx, ny, nz), offset)in mesh-local coordinates. Spheres that cross the plane are penalised during MorphIt optimization and hard-clamped afterwards. For non-MorphIt fit types, only the hard clamp is applied.None(default) disables clipping.device_cfg (curobo._src.types.device_cfg.DeviceCfg)
- Return type:
- Returns:
A
SphereFitResultwith sphere positions, radii, and optionally quality metrics.