Skip to content

chungmin99/ballpark

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

10 Commits
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Ballpark

Given a 3D mesh or a robot URDF, create a "ballpark" estimate of its spherical collision geometry.

Sphere decompositions for various robots

Features include:

  • Fast mesh-to-sphere decomposition via recursive PCA-based splitting.
  • Sphere set optimization with volume-based losses, and more.
  • Different presets for conservative, balanced, or surface-fitting sphere sets.

For robot URDFs, we also include:

  • Automatic sphere distribution across robot links, proportional to their geometry complexity.
  • Spheres are optimized on a robot-level to have minimal self-collision distance at rest pose.
  • Similar links are detected and share sphere parameters for visual and geometric consistency.
  • JSON export with sphere parameters for each link, and an ignore-list of link pairs for collision checking.

We also include a set of interactive visualization tools, supported via viser.

Installation

pip install -e .
pip install -e ".[examples]"
pip install -e ".[dev]"  # with development tools (linting, testing)

Quick Start

Mesh Spherization

import trimesh
from ballpark import spherize

# Load mesh
mesh = trimesh.load("object.stl")

# Generate spheres with adaptive fitting
spheres = spherize(mesh, target_spheres=32)

for s in spheres:
    print(f"center={s.center}, radius={s.radius}")

Robot URDF Spherization

import yourdfpy
from robot_descriptions.loaders.yourdfpy import load_robot_description
from ballpark import Robot, BallparkConfig, SpherePreset

# Load robot URDF with collision meshes
urdf = load_robot_description("panda_description")
urdf_coll = yourdfpy.URDF(
    robot=urdf.robot,
    load_collision_meshes=True,
)

# Create robot and generate spheres
robot = Robot(urdf_coll)
result = robot.spherize(target_spheres=100)

# Optional: refine with link- and robot-level costs
config = BallparkConfig.from_preset(SpherePreset.BALANCED)
result = robot.refine(result, config=config)

for link_name, spheres in result.link_spheres.items():
    print(f"{link_name}: {len(spheres)} spheres")

Manual Sphere Adjustments

We include an interactive script for adjusting the pose + radii of the auto-generated spheres.

Screen.Recording.2026-01-05.at.12.53.34.AM.mov

Acknowledgments

This project builds on ideas from:

About

Robot + mesh spherisation tool

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors

Languages