Public Types | Public Member Functions | List of all members
tesseract_collision::ContinuousContactManager Class Referenceabstract

#include <continuous_contact_manager.h>

Inheritance diagram for tesseract_collision::ContinuousContactManager:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const ContinuousContactManager >
 
using ConstUPtr = std::unique_ptr< const ContinuousContactManager >
 
using Ptr = std::shared_ptr< ContinuousContactManager >
 
using UPtr = std::unique_ptr< ContinuousContactManager >
 

Public Member Functions

virtual bool addCollisionObject (const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)=0
 Add a collision object to the checker. More...
 
virtual void applyContactManagerConfig (const ContactManagerConfig &config)
 Applies settings in the config. More...
 
virtual ContinuousContactManager::UPtr clone () const =0
 Clone the manager. More...
 
virtual void contactTest (ContactResultMap &collisions, const ContactRequest &request)=0
 Perform a contact test for all objects based. More...
 
 ContinuousContactManager ()=default
 
 ContinuousContactManager (const ContinuousContactManager &)=delete
 
 ContinuousContactManager (ContinuousContactManager &&)=delete
 
virtual bool disableCollisionObject (const std::string &name)=0
 Disable an object. More...
 
virtual bool enableCollisionObject (const std::string &name)=0
 Enable an object. More...
 
virtual const std::vector< std::string > & getActiveCollisionObjects () const =0
 Get which collision objects can move. More...
 
virtual const CollisionMarginDatagetCollisionMarginData () const =0
 Get the contact distance threshold. More...
 
virtual const CollisionShapesConstgetCollisionObjectGeometries (const std::string &name) const =0
 Get a collision objects collision geometries. More...
 
virtual const tesseract_common::VectorIsometry3dgetCollisionObjectGeometriesTransforms (const std::string &name) const =0
 Get a collision objects collision geometries transforms. More...
 
virtual const std::vector< std::string > & getCollisionObjects () const =0
 Get all collision objects. More...
 
virtual std::shared_ptr< const tesseract_common::ContactAllowedValidatorgetContactAllowedValidator () const =0
 Get the active function for determining if two links are allowed to be in collision. More...
 
virtual std::string getName () const =0
 Get the name of the contact manager. More...
 
virtual bool hasCollisionObject (const std::string &name) const =0
 Find if a collision object already exists. More...
 
virtual void incrementCollisionMargin (double increment)=0
 Increment the collision margin data by some value. More...
 
virtual bool isCollisionObjectEnabled (const std::string &name) const =0
 Check if collision object is enabled. More...
 
ContinuousContactManageroperator= (const ContinuousContactManager &)=delete
 
ContinuousContactManageroperator= (ContinuousContactManager &&)=delete
 
virtual bool removeCollisionObject (const std::string &name)=0
 Remove an object from the checker. More...
 
virtual void setActiveCollisionObjects (const std::vector< std::string > &names)=0
 Set which collision objects can move. More...
 
virtual void setCollisionMarginData (CollisionMarginData collision_margin_data)=0
 Set the contact distance threshold. More...
 
virtual void setCollisionMarginPair (const std::string &name1, const std::string &name2, double collision_margin)=0
 Set the margin for a given contact pair. More...
 
virtual void setCollisionMarginPairData (const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE)=0
 Set the pair contact distance thresholds for which collision should be considered on a per pair basis. More...
 
virtual void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose)=0
 Set a single static collision object's tansforms. More...
 
virtual void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)=0
 Set a single cast(moving) collision object's tansforms. More...
 
virtual void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &pose1, const tesseract_common::VectorIsometry3d &pose2)=0
 Set a series of cast(moving) collision object's tranforms. More...
 
virtual void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses)=0
 Set a series of static collision object's tranforms. More...
 
virtual void setCollisionObjectsTransform (const tesseract_common::TransformMap &pose1, const tesseract_common::TransformMap &pose2)=0
 Set a series of cast(moving) collision object's tranforms. More...
 
virtual void setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms)=0
 Set a series of static collision object's tranforms. More...
 
virtual void setContactAllowedValidator (std::shared_ptr< const tesseract_common::ContactAllowedValidator > validator)=0
 Set the active function for determining if two links are allowed to be in collision. More...
 
virtual void setDefaultCollisionMargin (double default_collision_margin)=0
 Set the default collision margin. More...
 
virtual ~ContinuousContactManager ()=default
 

Detailed Description

Definition at line 41 of file continuous_contact_manager.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 47 of file continuous_contact_manager.h.

◆ ConstUPtr

Definition at line 49 of file continuous_contact_manager.h.

◆ Ptr

Definition at line 46 of file continuous_contact_manager.h.

◆ UPtr

Definition at line 48 of file continuous_contact_manager.h.

Constructor & Destructor Documentation

◆ ContinuousContactManager() [1/3]

tesseract_collision::ContinuousContactManager::ContinuousContactManager ( )
default

◆ ~ContinuousContactManager()

virtual tesseract_collision::ContinuousContactManager::~ContinuousContactManager ( )
virtualdefault

◆ ContinuousContactManager() [2/3]

tesseract_collision::ContinuousContactManager::ContinuousContactManager ( const ContinuousContactManager )
delete

◆ ContinuousContactManager() [3/3]

tesseract_collision::ContinuousContactManager::ContinuousContactManager ( ContinuousContactManager &&  )
delete

Member Function Documentation

◆ addCollisionObject()

virtual bool tesseract_collision::ContinuousContactManager::addCollisionObject ( const std::string &  name,
const int &  mask_id,
const CollisionShapesConst shapes,
const tesseract_common::VectorIsometry3d shape_poses,
bool  enabled = true 
)
pure virtual

Add a collision object to the checker.

All objects are added should initially be added as static objects. Use the setContactRequest method of defining which collision objects are moving.

Parameters
nameThe name of the object, must be unique.
mask_idUser defined id which gets stored in the results structure.
shapesA vector of shapes that make up the collision object.
shape_posesA vector of poses for each shape, must be same length as shapes
shape_typesA vector of shape types for encode the collision object. If the vector is of length 1 it is used for all shapes.
collision_object_typesA int identifying a conversion mode for the object. (ex. convert meshes to convex_hulls)
enabledIndicate if the object is enabled for collision checking.
Returns
true if successfully added, otherwise false.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ applyContactManagerConfig()

void tesseract_collision::ContinuousContactManager::applyContactManagerConfig ( const ContactManagerConfig config)
virtual

Applies settings in the config.

Parameters
configSettings to be applies

Definition at line 32 of file continuous_contact_manager.cpp.

◆ clone()

virtual ContinuousContactManager::UPtr tesseract_collision::ContinuousContactManager::clone ( ) const
pure virtual

Clone the manager.

This is to be used for multi threaded application. A user should make a clone for each thread.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ contactTest()

virtual void tesseract_collision::ContinuousContactManager::contactTest ( ContactResultMap collisions,
const ContactRequest request 
)
pure virtual

Perform a contact test for all objects based.

Parameters
collisionsThe Contact results data
typeThe type of contact test

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ disableCollisionObject()

virtual bool tesseract_collision::ContinuousContactManager::disableCollisionObject ( const std::string &  name)
pure virtual

◆ enableCollisionObject()

virtual bool tesseract_collision::ContinuousContactManager::enableCollisionObject ( const std::string &  name)
pure virtual

◆ getActiveCollisionObjects()

virtual const std::vector<std::string>& tesseract_collision::ContinuousContactManager::getActiveCollisionObjects ( ) const
pure virtual

Get which collision objects can move.

Returns
A list of collision object names

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ getCollisionMarginData()

virtual const CollisionMarginData& tesseract_collision::ContinuousContactManager::getCollisionMarginData ( ) const
pure virtual

◆ getCollisionObjectGeometries()

virtual const CollisionShapesConst& tesseract_collision::ContinuousContactManager::getCollisionObjectGeometries ( const std::string &  name) const
pure virtual

Get a collision objects collision geometries.

Parameters
nameThe collision objects name
Returns
A vector of collision geometries. The vector will be empty if the collision object is not found.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ getCollisionObjectGeometriesTransforms()

virtual const tesseract_common::VectorIsometry3d& tesseract_collision::ContinuousContactManager::getCollisionObjectGeometriesTransforms ( const std::string &  name) const
pure virtual

Get a collision objects collision geometries transforms.

Parameters
nameThe collision objects name
Returns
A vector of collision geometries transforms. The vector will be empty if the collision object is not found.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ getCollisionObjects()

virtual const std::vector<std::string>& tesseract_collision::ContinuousContactManager::getCollisionObjects ( ) const
pure virtual

◆ getContactAllowedValidator()

virtual std::shared_ptr<const tesseract_common::ContactAllowedValidator> tesseract_collision::ContinuousContactManager::getContactAllowedValidator ( ) const
pure virtual

Get the active function for determining if two links are allowed to be in collision.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ getName()

virtual std::string tesseract_collision::ContinuousContactManager::getName ( ) const
pure virtual

◆ hasCollisionObject()

virtual bool tesseract_collision::ContinuousContactManager::hasCollisionObject ( const std::string &  name) const
pure virtual

Find if a collision object already exists.

Parameters
nameThe name of the collision object
Returns
true if it exists, otherwise false.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ incrementCollisionMargin()

virtual void tesseract_collision::ContinuousContactManager::incrementCollisionMargin ( double  increment)
pure virtual

Increment the collision margin data by some value.

Parameters
incrementThe value to increment the collision margin value

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager, and tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager.

◆ isCollisionObjectEnabled()

virtual bool tesseract_collision::ContinuousContactManager::isCollisionObjectEnabled ( const std::string &  name) const
pure virtual

Check if collision object is enabled.

Parameters
nameThe name of the object
Returns
True if enabled, otherwise false

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ operator=() [1/2]

ContinuousContactManager& tesseract_collision::ContinuousContactManager::operator= ( const ContinuousContactManager )
delete

◆ operator=() [2/2]

ContinuousContactManager& tesseract_collision::ContinuousContactManager::operator= ( ContinuousContactManager &&  )
delete

◆ removeCollisionObject()

virtual bool tesseract_collision::ContinuousContactManager::removeCollisionObject ( const std::string &  name)
pure virtual

Remove an object from the checker.

Parameters
nameThe name of the object
Returns
true if successfully removed, otherwise false.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setActiveCollisionObjects()

virtual void tesseract_collision::ContinuousContactManager::setActiveCollisionObjects ( const std::vector< std::string > &  names)
pure virtual

Set which collision objects can move.

Parameters
namesA vector of collision object names

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionMarginData()

virtual void tesseract_collision::ContinuousContactManager::setCollisionMarginData ( CollisionMarginData  collision_margin_data)
pure virtual

Set the contact distance threshold.

Parameters
collision_margin_dataThe contact distance

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionMarginPair()

virtual void tesseract_collision::ContinuousContactManager::setCollisionMarginPair ( const std::string &  name1,
const std::string &  name2,
double  collision_margin 
)
pure virtual

Set the margin for a given contact pair.

The order of the object names does not matter, that is handled internal to the class.

Parameters
obj1The first object name. Order doesn't matter
obj2The Second object name. Order doesn't matter
collision_margincontacts with distance < collision_margin are considered in collision

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionMarginPairData()

virtual void tesseract_collision::ContinuousContactManager::setCollisionMarginPairData ( const CollisionMarginPairData pair_margin_data,
CollisionMarginPairOverrideType  override_type = CollisionMarginPairOverrideType::REPLACE 
)
pure virtual

Set the pair contact distance thresholds for which collision should be considered on a per pair basis.

Parameters
pair_margin_dataContains the pair collision margins that will replace the current settings
override_typeThis determines how the provided CollisionMarginData is applied

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [1/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose 
)
pure virtual

Set a single static collision object's tansforms.

Parameters
nameThe name of the object
poseThe tranformation in world

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [2/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose1,
const Eigen::Isometry3d &  pose2 
)
pure virtual

Set a single cast(moving) collision object's tansforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
nameThe name of the object
pose1The start tranformation in world
pose2The end tranformation in world

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [3/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const std::vector< std::string > &  names,
const tesseract_common::VectorIsometry3d pose1,
const tesseract_common::VectorIsometry3d pose2 
)
pure virtual

Set a series of cast(moving) collision object's tranforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
namesThe name of the object
pose1The start tranformations in world
pose2The end tranformations in world

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [4/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const std::vector< std::string > &  names,
const tesseract_common::VectorIsometry3d poses 
)
pure virtual

Set a series of static collision object's tranforms.

Parameters
namesThe name of the object
posesThe tranformation in world

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [5/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const tesseract_common::TransformMap pose1,
const tesseract_common::TransformMap pose2 
)
pure virtual

Set a series of cast(moving) collision object's tranforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
pose1A start transform map <name, pose>
pose2A end transform map <name, pose>

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setCollisionObjectsTransform() [6/6]

virtual void tesseract_collision::ContinuousContactManager::setCollisionObjectsTransform ( const tesseract_common::TransformMap transforms)
pure virtual

Set a series of static collision object's tranforms.

Parameters
transformsA transform map <name, pose>

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setContactAllowedValidator()

virtual void tesseract_collision::ContinuousContactManager::setContactAllowedValidator ( std::shared_ptr< const tesseract_common::ContactAllowedValidator validator)
pure virtual

Set the active function for determining if two links are allowed to be in collision.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.

◆ setDefaultCollisionMargin()

virtual void tesseract_collision::ContinuousContactManager::setDefaultCollisionMargin ( double  default_collision_margin)
pure virtual

Set the default collision margin.

Parameters
default_collision_marginNew default collision margin

Implemented in tesseract_collision::tesseract_collision_bullet::BulletCastBVHManager, and tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager.


The documentation for this class was generated from the following files:


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53