Collision Checker Module User Guideο
This guide covers the ManipulaPy.potential_field.CollisionChecker class,
which performs geometry-based self-collision detection for serial manipulators
using URDF meshes.
Note
Examples target Python 3.10+, SciPy 1.10+, and the urchin.urdf parser
for loading URDF meshes and building convex hulls for collision tests.
Introductionο
Collision checking is essential for safe motion planning. The
CollisionChecker builds convex-hull approximations of each linkβs visual mesh
and tests for pairwise intersection at a given robot configuration.
Key featuresο
Convex hull construction from URDF mesh vertices
Fast pairwise collision tests using convex polytope intersection checks
Pose transforms of hulls via forward kinematics
Self-collision detection between any two non-adjacent links
Mathematical Backgroundο
Given a robot configuration \(\mathbf q\) (joint angles), the forward-kinematics function \(T_i(\mathbf q)\in SE(3)\) returns the homogeneous transform of link i. Each linkβs mesh is approximated by its convex hull \(H_i\). Under transform \(T_i\), hull vertices map to
Two convex polyhedra intersect iff their convex hulls intersect. In practice, the check can be implemented by half-space evaluations or separating-axis tests on the transformed hulls.
Workflowο
Load URDF β extract mesh vertices.
Build hulls \(\{H_i\}\) offline.
For each configuration \(\mathbf q\): - Compute \(T_i(\mathbf q)\) for each link. - Transform \(H_i \rightarrow T_i(H_i)\). - Test all pairs (i, j) with j > i + 1 (skip adjacent links) for intersection. - If any pair intersects β collision.
API Referenceο
- class ManipulaPy.potential_field.CollisionChecker(urdf_path, backend='builtin', load_meshes=True)[source]ο
Collision checker using URDF visual/collision geometry and convex hulls.
- Supports multiple URDF parser backends:
βbuiltinβ: Native ManipulaPy parser (NumPy 2.0 compatible, default)
βurchinβ: Legacy urchin parser (requires urchin, not NumPy 2.0 compatible)
βpybulletβ: PyBullet-based parser (requires pybullet)
Installationο
Ensure dependencies are installed:
pip install manipulapy[core] scipy urchin
Usage Examplesο
Basic collision checkο
from ManipulaPy.potential_field import CollisionChecker
# Initialize with your robot URDF
cc = CollisionChecker("robot.urdf")
# Test a single joint configuration
q = [0.0, -0.5, 0.3, 0.0, 0.2, -0.1]
if cc.check_collision(q):
print("In collision!")
else:
print("Collision-free.")
Batch checkingο
from ManipulaPy.potential_field import CollisionChecker
import numpy as np
cc = CollisionChecker("robot.urdf")
poses = np.random.uniform(-0.5, 0.5, size=(100, 6))
collisions = [cc.check_collision(q) for q in poses]
print(f"{sum(collisions)} / {len(poses)} configurations in collision")
Integration with trajectory planningο
from ManipulaPy.path_planning import TrajectoryPlanning
from ManipulaPy.potential_field import CollisionChecker
planner = TrajectoryPlanning(robot, "robot.urdf", dynamics, joint_limits)
cc = CollisionChecker("robot.urdf")
traj = planner.joint_trajectory(q_start, q_goal, Tf=2.0, N=200, method=3)
safe = []
for q in traj["positions"]:
if not cc.check_collision(q):
safe.append(q)
print(f"{len(safe)} collision-free waypoints")
Advanced Topicsο
Skipping adjacent linksο
By default, check_collision skips link pairs that are mechanically adjacent
to avoid false positives at shared joints.
Convex hull cachingο
Hulls are built once at initialization. For dynamic meshes, you can rebuild via
cc._create_convex_hulls() (may be expensive; prefer offline caching).
Custom mesh precisionο
Simplify (decimate) meshes before hull construction to reduce hull size and speed up intersection tests.
Troubleshootingο
Mesh loading errorsο
Ensure your URDFβs <mesh> elements point to files with valid vertex arrays.
False negatives/positivesο
Convex hulls approximate concave geometry. For high precision, refine meshes or augment with additional proxy geometry.
Performance bottlenecksο
Precompute and cache hulls.
Use fewer sample configurations in look-ahead checks.
Parallelize
check_collisioncalls with multiprocessing.
See Alsoο
Trajectory Planning User Guide β generating joint trajectories
Perception User Guide β environment sensing and obstacle extraction
Simulation Module User Guide β PyBullet-based simulation
Referencesο
SciPy ConvexHull documentation: https://docs.scipy.org/doc/scipy/reference/generated/scipy.spatial.ConvexHull.html
urchin.urdfβ URDF parser for PythonLatombe, J.-C., Robot Motion Planning, Kluwer, 1991
Ericson, C., Real-Time Collision Detection, Morgan Kaufmann, 2005