Tesseract 0.28.4
Loading...
Searching...
No Matches
Collision Detection

Tesseract's collision checking system supports discrete and continuous contact queries with a plugin-based architecture.

Tesseract provides a high-performance collision checking system that understands nothing about robot connectivity — it purely manages collision objects, their transforms, and contact queries. This separation of concerns makes the collision system flexible and reusable across different contexts.

Continuous Collision Detection

Overview

The collision system supports two modes of operation:

  • Discrete Collision Checking — Tests for contact at a single configuration. Used during planning to evaluate candidate states.
  • Continuous Collision Checking — Tests for contact along a swept motion between two configurations. Used for trajectory validation to catch collisions that discrete checks miss.

Contact Manager Plugin Configuration

Contact managers are loaded as plugins through a YAML configuration file referenced in the SRDF. This allows you to swap collision backends without changing any application code.

The configuration has four sections:

Section Description
search_paths Directories to search for plugin libraries (searched in order)
search_libraries Specific libraries to search for plugin classes
discrete_plugins Discrete contact manager plugin definitions
continuous_plugins Continuous contact manager plugin definitions

Example Configuration:**

contact_manager_plugins:
search_paths:
- /usr/local/lib
search_libraries:
- tesseract_collision_bullet_factories
- tesseract_collision_fcl_factories
discrete_plugins:
default: BulletDiscreteBVHManager
plugins:
BulletDiscreteBVHManager:
class: BulletDiscreteBVHManagerFactory
BulletDiscreteSimpleManager:
class: BulletDiscreteSimpleManagerFactory
FCLDiscreteBVHManager:
class: FCLDiscreteBVHManagerFactory
continuous_plugins:
default: BulletCastBVHManager
plugins:
BulletCastBVHManager:
class: BulletCastBVHManagerFactory
BulletCastSimpleManager:
class: BulletCastSimpleManagerFactory

Features

The collision system provides these core capabilities:

  1. Add collision objects (links) to the checker
  2. Set link transforms
  3. Enable/Disable individual links
  4. Set a default contact distance threshold
  5. Set per-link-pair contact distance thresholds
  6. Perform different contact test types (FIRST, CLOSEST, ALL)

Contact Test Types

The contact test type controls how many contacts are reported per query:

Contact Test Type Description Best For
ContactTestType::FIRST Exit on first contact found Planners like Descartes and OMPL that only need a boolean collision check
ContactTestType::CLOSEST Store only the closest contact for each collision object pair Planners like TrajOpt that need distance gradients
ContactTestType::ALL Store all contacts for each collision object pair Detailed analysis, TrajOpt with full contact information

Available Contact Checkers

Contact Checker Type Description
BulletDiscreteBVHManager Discrete Leverages Bullet Physics BVH for discrete contact checking
BulletCastBVHManager Continuous Uses Bullet Physics BVH with casted convex hulls between two link poses
BulletDiscreteSimpleManager Discrete Naive Bullet implementation that loops over all pairs. Can be faster in small environments.
BulletCastSimpleManager Continuous Naive continuous implementation with pair-wise loops. Can be faster in small environments.
FCLDiscreteBVHManager Discrete Uses the Flexible Collision Library (FCL) for discrete contact checking
GPUDiscreteBVHManager Discrete GPU/CPU accelerated contact checking

Performance Benchmarks

Tesseract's Bullet-based collision checking is significantly faster than FCL across all contact test types:

FCL Comparison (Tesseract Bullet vs FCL)**

Test Mode FIRST CLOSEST ALL
Contact Only 3x Faster 19x Faster 19x Faster
Penetration 2x Faster 15x Faster 15x Faster
Distance 6,000x Faster 265x Faster 265x Faster
Benchmark — Contact Test Type: FIRST
Benchmark — Contact Test Type: CLOSEST
Benchmark — Contact Test Type: ALL

Example

See the Box-Box Collision Example for a complete walkthrough that demonstrates:

  • Creating a contact checker
  • Adding collision objects (enabled and disabled)
  • Creating convex hulls from mesh files
  • Setting active collision objects
  • Configuring contact distance thresholds
  • Setting object transforms
  • Performing collision checks at different distances

Next Steps