Skip to content

tesseract_robotics.tesseract_collision

Collision detection managers and contact queries.

Contact Managers

DiscreteContactManager

Checks collision at a single configuration.

Python
from tesseract_robotics.tesseract_collision import DiscreteContactManager

# Get from environment
manager = env.getDiscreteContactManager()

# Clone for thread safety
my_manager = manager.clone()

# Set collision objects state
my_manager.setCollisionObjectsTransform(link_transforms)

# Run collision check
my_manager.contactTest(result_map, request)

ContinuousContactManager

Checks collision along swept motion.

Python
from tesseract_robotics.tesseract_collision import ContinuousContactManager

# Get from environment
manager = env.getContinuousContactManager()

# Clone for thread safety
my_manager = manager.clone()

# Set start and end transforms
my_manager.setCollisionObjectsTransform(
    link_transforms_start,
    link_transforms_end
)

# Run continuous collision check
my_manager.contactTest(result_map, request)

Contact Request

Configure what contacts to find.

Python
from tesseract_robotics.tesseract_collision import (
    ContactRequest, ContactTestType
)

request = ContactRequest()
request.type = ContactTestType.ALL  # find all contacts

# Alternatively
request.type = ContactTestType.FIRST    # stop at first contact
request.type = ContactTestType.CLOSEST  # only closest contact
request.type = ContactTestType.LIMITED  # up to max contacts
ContactTestType Description
FIRST Stop at first contact found
CLOSEST Only return closest contact
ALL Return all contacts
LIMITED Return up to N contacts

Contact Results

ContactResult

Single contact between two objects.

Python
from tesseract_robotics.tesseract_collision import ContactResult

# After contactTest()
for key, results in result_map.items():
    for contact in results:
        print(f"Contact: {contact.link_names[0]} <-> {contact.link_names[1]}")
        print(f"  Distance: {contact.distance}")
        print(f"  Point A: {contact.nearest_points[0]}")
        print(f"  Point B: {contact.nearest_points[1]}")
        print(f"  Normal: {contact.normal}")
Attribute Type Description
link_names tuple[str, str] Colliding link names
distance float Signed distance (negative = penetration)
nearest_points tuple[np.array, np.array] Contact points
normal np.array Contact normal (A to B)
cc_time tuple[float, float] Continuous collision times

ContactResultMap

Dictionary of contacts by link pair.

Python
from tesseract_robotics.tesseract_collision import ContactResultMap

result_map = ContactResultMap()
manager.contactTest(result_map, request)

# Iterate results
for pair_key, contacts in result_map.items():
    print(f"Pair {pair_key}: {len(contacts)} contacts")

ContactResultVector

List of contact results.

Python
from tesseract_robotics.tesseract_collision import ContactResultVector

# Flatten all contacts
all_contacts = ContactResultVector()
for contacts in result_map.values():
    all_contacts.extend(contacts)

Configuration

CollisionCheckConfig

Configure collision checking behavior.

Python
from tesseract_robotics.tesseract_collision import CollisionCheckConfig

config = CollisionCheckConfig()
config.contact_request = request
config.longest_valid_segment_length = 0.01  # for continuous

ContactManagerConfig

Configure contact manager settings.

Python
from tesseract_robotics.tesseract_collision import ContactManagerConfig

config = ContactManagerConfig()
config.margin_data.setDefaultCollisionMargin(0.025)
config.margin_data.setPairCollisionMargin("link_a", "link_b", 0.05)

Convex Mesh Generation

Generate convex hulls for collision.

Python
from tesseract_robotics.tesseract_collision import makeConvexMesh

# From vertices
vertices = [np.array([x, y, z]) for ...]
convex = makeConvexMesh(vertices)

Collision Evaluator Types

Used with trajectory optimization.

Python
from tesseract_robotics.tesseract_collision import CollisionEvaluatorType

CollisionEvaluatorType.DISCRETE           # single config
CollisionEvaluatorType.LVS_DISCRETE       # interpolated discrete
CollisionEvaluatorType.LVS_CONTINUOUS     # swept volume
CollisionEvaluatorType.CONTINUOUS         # continuous

Usage Example

Python
from tesseract_robotics.tesseract_collision import (
    ContactRequest, ContactTestType, ContactResultMap
)

# Setup
manager = env.getDiscreteContactManager().clone()
request = ContactRequest()
request.type = ContactTestType.ALL

# Set state
env.setState(joint_values)
state = env.getState()
manager.setCollisionObjectsTransform(state.link_transforms)

# Check collision
results = ContactResultMap()
manager.contactTest(results, request)

# Process results
is_collision = len(results) > 0
if is_collision:
    for contacts in results.values():
        for c in contacts:
            if c.distance < 0:
                print(f"Penetration: {c.link_names} depth={-c.distance:.4f}")

Auto-generated API Reference

ContactTestType_FIRST module-attribute

Python
ContactTestType_FIRST: ContactTestType = FIRST

ContactTestType_CLOSEST module-attribute

Python
ContactTestType_CLOSEST: ContactTestType = CLOSEST

ContactTestType_ALL module-attribute

Python
ContactTestType_ALL: ContactTestType = ALL

ContactTestType_LIMITED module-attribute

Python
ContactTestType_LIMITED: ContactTestType = LIMITED

ContinuousCollisionType

Bases: Enum

CCType_None class-attribute instance-attribute

Python
CCType_None = 0

CCType_Time0 class-attribute instance-attribute

Python
CCType_Time0 = 1

CCType_Time1 class-attribute instance-attribute

Python
CCType_Time1 = 2

CCType_Between class-attribute instance-attribute

Python
CCType_Between = 3

ContactTestType

Bases: Enum

FIRST class-attribute instance-attribute

Python
FIRST = 0

CLOSEST class-attribute instance-attribute

Python
CLOSEST = 1

ALL class-attribute instance-attribute

Python
ALL = 2

LIMITED class-attribute instance-attribute

Python
LIMITED = 3

CollisionEvaluatorType

Bases: Enum

NONE class-attribute instance-attribute

Python
NONE = 0

DISCRETE class-attribute instance-attribute

Python
DISCRETE = 1

LVS_DISCRETE class-attribute instance-attribute

Python
LVS_DISCRETE = 2

CONTINUOUS class-attribute instance-attribute

Python
CONTINUOUS = 3

LVS_CONTINUOUS class-attribute instance-attribute

Python
LVS_CONTINUOUS = 4

CollisionCheckProgramType

Bases: Enum

ALL class-attribute instance-attribute

Python
ALL = 0

ALL_EXCEPT_START class-attribute instance-attribute

Python
ALL_EXCEPT_START = 1

ALL_EXCEPT_END class-attribute instance-attribute

Python
ALL_EXCEPT_END = 2

START_ONLY class-attribute instance-attribute

Python
START_ONLY = 3

END_ONLY class-attribute instance-attribute

Python
END_ONLY = 4

INTERMEDIATE_ONLY class-attribute instance-attribute

Python
INTERMEDIATE_ONLY = 5

ACMOverrideType

Bases: Enum

NONE class-attribute instance-attribute

Python
NONE = 0

ASSIGN class-attribute instance-attribute

Python
ASSIGN = 1

AND class-attribute instance-attribute

Python
AND = 2

OR class-attribute instance-attribute

Python
OR = 3

ContactResult

distance property writable

Python
distance: float

type_id property writable

Python
type_id: list[int]
Python
link_names: list[str]

shape_id property writable

Python
shape_id: list[int]

nearest_points property writable

Python
nearest_points: list[Annotated[NDArray[float64], dict(shape=3, order=C)]]

transform property writable

Python
transform: list['Eigen::Transform<double, 3, 1, 0>']

normal property writable

Python
normal: Annotated[NDArray[float64], dict(shape=3, order=C)]

single_contact_point property writable

Python
single_contact_point: bool

__init__

Python
__init__() -> None

clear

Python
clear() -> None

ContactResultVector

__init__

Python
__init__() -> None

__len__

Python
__len__() -> int

__getitem__

Python
__getitem__(arg: int) -> ContactResult

append

Python
append(arg: ContactResult) -> None

clear

Python
clear() -> None

ContactResultMap

__init__

Python
__init__() -> None

count

Python
count() -> int

size

Python
size() -> int

empty

Python
empty() -> bool

clear

Python
clear() -> None

release

Python
release() -> None

getSummary

Python
getSummary() -> str

flattenCopyResults

Python
flattenCopyResults() -> ContactResultVector

flattenMoveResults

Python
flattenMoveResults(results: ContactResultVector) -> None

__len__

Python
__len__() -> int

ContactRequest

type property writable

Python
type: ContactTestType

calculate_penetration property writable

Python
calculate_penetration: bool

calculate_distance property writable

Python
calculate_distance: bool

contact_limit property writable

Python
contact_limit: int

ContactManagerConfig

default_margin property writable

Python
default_margin: float | None

pair_margin_override_type property writable

Python
pair_margin_override_type: 'tesseract_common::CollisionMarginPairOverrideType'

acm_override_type property writable

Python
acm_override_type: ACMOverrideType

margin_data_override_type property writable

Python
margin_data_override_type: 'tesseract_common::CollisionMarginPairOverrideType'

CollisionCheckConfig

contact_request property writable

Python
contact_request: ContactRequest

type property writable

Python
type: CollisionEvaluatorType

longest_valid_segment_length property writable

Python
longest_valid_segment_length: float

check_program_mode property writable

Python
check_program_mode: CollisionCheckProgramType

__init__

Python
__init__() -> None

DiscreteContactManager

getName

Python
getName() -> str

hasCollisionObject

Python
hasCollisionObject(name: str) -> bool

removeCollisionObject

Python
removeCollisionObject(name: str) -> bool

enableCollisionObject

Python
enableCollisionObject(name: str) -> bool

disableCollisionObject

Python
disableCollisionObject(name: str) -> bool

isCollisionObjectEnabled

Python
isCollisionObjectEnabled(name: str) -> bool

getCollisionObjects

Python
getCollisionObjects() -> list[str]

setActiveCollisionObjects

Python
setActiveCollisionObjects(names: Sequence[str]) -> None

getActiveCollisionObjects

Python
getActiveCollisionObjects() -> list[str]

setDefaultCollisionMargin

Python
setDefaultCollisionMargin(default_collision_margin: float) -> None

setCollisionMarginPair

Python
setCollisionMarginPair(name1: str, name2: str, collision_margin: float) -> None

setCollisionMarginData

Python
setCollisionMarginData(collision_margin_data: 'tesseract_common::CollisionMarginData') -> None

setDefaultCollisionMarginData

Python
setDefaultCollisionMarginData(default_collision_margin: float) -> None

setPairCollisionMarginData

Python
setPairCollisionMarginData(name1: str, name2: str, collision_margin: float) -> None

getCollisionMarginData

Python
getCollisionMarginData() -> 'tesseract_common::CollisionMarginData'

addCollisionObject

Python
addCollisionObject(name: str, mask_id: int, shapes: Sequence['tesseract_geometry::Geometry'], shape_poses: Sequence['Eigen::Transform<double, 3, 1, 0>'], enabled: bool = True) -> bool

getCollisionObjectGeometries

Python
getCollisionObjectGeometries(name: str) -> list['tesseract_geometry::Geometry']

getCollisionObjectGeometriesTransforms

Python
getCollisionObjectGeometriesTransforms(name: str) -> list['Eigen::Transform<double, 3, 1, 0>']

contactTest

Python
contactTest(collisions: ContactResultMap, request: ContactRequest) -> None

ContinuousContactManager

getName

Python
getName() -> str

hasCollisionObject

Python
hasCollisionObject(name: str) -> bool

removeCollisionObject

Python
removeCollisionObject(name: str) -> bool

enableCollisionObject

Python
enableCollisionObject(name: str) -> bool

disableCollisionObject

Python
disableCollisionObject(name: str) -> bool

isCollisionObjectEnabled

Python
isCollisionObjectEnabled(name: str) -> bool

setCollisionObjectsTransform

Python
setCollisionObjectsTransform(name: str, pose: 'Eigen::Transform<double, 3, 1, 0>') -> None

setCollisionObjectsTransformCast

Python
setCollisionObjectsTransformCast(name: str, pose1: 'Eigen::Transform<double, 3, 1, 0>', pose2: 'Eigen::Transform<double, 3, 1, 0>') -> None

getCollisionObjects

Python
getCollisionObjects() -> list[str]

setActiveCollisionObjects

Python
setActiveCollisionObjects(names: Sequence[str]) -> None

getActiveCollisionObjects

Python
getActiveCollisionObjects() -> list[str]

setDefaultCollisionMargin

Python
setDefaultCollisionMargin(default_collision_margin: float) -> None

setCollisionMarginPair

Python
setCollisionMarginPair(name1: str, name2: str, collision_margin: float) -> None

setDefaultCollisionMarginData

Python
setDefaultCollisionMarginData(default_collision_margin: float) -> None

setPairCollisionMarginData

Python
setPairCollisionMarginData(name1: str, name2: str, collision_margin: float) -> None

contactTest

Python
contactTest(collisions: ContactResultMap, request: ContactRequest) -> None

ContactManagersPluginFactory

addSearchPath

Python
addSearchPath(path: str) -> None

getSearchPaths

Python
getSearchPaths() -> list[str]

addSearchLibrary

Python
addSearchLibrary(library_name: str) -> None

getSearchLibraries

Python
getSearchLibraries() -> list[str]

hasDiscreteContactManagerPlugins

Python
hasDiscreteContactManagerPlugins() -> bool

getDefaultDiscreteContactManagerPlugin

Python
getDefaultDiscreteContactManagerPlugin() -> str

hasContinuousContactManagerPlugins

Python
hasContinuousContactManagerPlugins() -> bool

getDefaultContinuousContactManagerPlugin

Python
getDefaultContinuousContactManagerPlugin() -> str

createDiscreteContactManager

Python
createDiscreteContactManager(name: str) -> DiscreteContactManager

createContinuousContactManager

Python
createContinuousContactManager(name: str) -> ContinuousContactManager

makeConvexMesh

Python
makeConvexMesh(mesh: 'tesseract_geometry::Mesh') -> 'tesseract_geometry::ConvexMesh'

Create a ConvexMesh from a Mesh using bullet's convex hull algorithm