Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
tesseract_collision::DiscreteContactManager Class Referenceabstract

#include <discrete_contact_manager.h>

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

Public Types

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

Public Member Functions

 DiscreteContactManager ()=default
 
virtual ~DiscreteContactManager ()=default
 
 DiscreteContactManager (const DiscreteContactManager &)=delete
 
DiscreteContactManageroperator= (const DiscreteContactManager &)=delete
 
 DiscreteContactManager (DiscreteContactManager &&)=delete
 
DiscreteContactManageroperator= (DiscreteContactManager &&)=delete
 
virtual std::string getName () const =0
 Get the name of the contact manager. More...
 
virtual DiscreteContactManager::UPtr clone () const =0
 Clone the manager. More...
 
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 object to the checker. 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 bool hasCollisionObject (const std::string &name) const =0
 Find if a collision object already exists. More...
 
virtual bool removeCollisionObject (const std::string &name)=0
 Remove an object from the checker. More...
 
virtual bool enableCollisionObject (const std::string &name)=0
 Enable an object. More...
 
virtual bool disableCollisionObject (const std::string &name)=0
 Disable an object. More...
 
virtual bool isCollisionObjectEnabled (const std::string &name) const =0
 Check if collision object is enabled. More...
 
virtual void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose)=0
 Set a single collision object's transforms. More...
 
virtual void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses)=0
 Set a series of collision object's transforms. More...
 
virtual void setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms)=0
 Set a series of collision object's transforms. More...
 
virtual const std::vector< std::string > & getCollisionObjects () const =0
 Get all collision objects. More...
 
virtual void setActiveCollisionObjects (const std::vector< std::string > &names)=0
 Set which collision objects can move. More...
 
virtual const std::vector< std::string > & getActiveCollisionObjects () const =0
 Get which collision objects can move. More...
 
virtual void setCollisionMarginData (CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE)=0
 Set the contact distance thresholds for which collision should be considered on a per pair basis. More...
 
virtual void setDefaultCollisionMarginData (double default_collision_margin)=0
 Set the default collision margin. More...
 
virtual void setPairCollisionMarginData (const std::string &name1, const std::string &name2, double collision_margin)=0
 Set the margin for a given contact pair. More...
 
virtual const CollisionMarginDatagetCollisionMarginData () const =0
 Get the contact distance threshold. More...
 
virtual void setIsContactAllowedFn (IsContactAllowedFn fn)=0
 Set the active function for determining if two links are allowed to be in collision. More...
 
virtual IsContactAllowedFn getIsContactAllowedFn () const =0
 Get the active function for determining if two links are allowed to be in collision. More...
 
virtual void contactTest (ContactResultMap &collisions, const ContactRequest &request)=0
 Perform a contact test for all objects based. More...
 
virtual void applyContactManagerConfig (const ContactManagerConfig &config)
 Applies settings in the config. More...
 

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ DiscreteContactManager() [1/3]

tesseract_collision::DiscreteContactManager::DiscreteContactManager ( )
default

◆ ~DiscreteContactManager()

virtual tesseract_collision::DiscreteContactManager::~DiscreteContactManager ( )
virtualdefault

◆ DiscreteContactManager() [2/3]

tesseract_collision::DiscreteContactManager::DiscreteContactManager ( const DiscreteContactManager )
delete

◆ DiscreteContactManager() [3/3]

tesseract_collision::DiscreteContactManager::DiscreteContactManager ( DiscreteContactManager &&  )
delete

Member Function Documentation

◆ addCollisionObject()

virtual bool tesseract_collision::DiscreteContactManager::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 object to the checker.

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
Returns
true if successfully added, otherwise false.

Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ applyContactManagerConfig()

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

Applies settings in the config.

Parameters
configSettings to be applies

◆ clone()

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

◆ contactTest()

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

Perform a contact test for all objects based.

Parameters
collisionsThe contact results data
requestThe contact request data

Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ disableCollisionObject()

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

◆ enableCollisionObject()

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

◆ getActiveCollisionObjects()

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

◆ getCollisionMarginData()

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

◆ getCollisionObjectGeometries()

virtual const CollisionShapesConst & tesseract_collision::DiscreteContactManager::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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ getCollisionObjectGeometriesTransforms()

virtual const tesseract_common::VectorIsometry3d & tesseract_collision::DiscreteContactManager::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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ getCollisionObjects()

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

◆ getIsContactAllowedFn()

virtual IsContactAllowedFn tesseract_collision::DiscreteContactManager::getIsContactAllowedFn ( ) const
pure virtual

◆ getName()

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

◆ hasCollisionObject()

virtual bool tesseract_collision::DiscreteContactManager::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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ isCollisionObjectEnabled()

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

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ removeCollisionObject()

virtual bool tesseract_collision::DiscreteContactManager::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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ setActiveCollisionObjects()

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

◆ setCollisionMarginData()

virtual void tesseract_collision::DiscreteContactManager::setCollisionMarginData ( CollisionMarginData  collision_margin_data,
CollisionMarginOverrideType  override_type = CollisionMarginOverrideType::REPLACE 
)
pure virtual

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

Parameters
collision_margin_dataContains the data that will replace the current settings
override_typeThis determines how the provided CollisionMarginData is applied

Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ setCollisionObjectsTransform() [1/3]

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

◆ setCollisionObjectsTransform() [2/3]

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

Set a series of collision object's transforms.

Parameters
namesThe name of the object
posesThe transformation in world

Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.

◆ setCollisionObjectsTransform() [3/3]

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

◆ setDefaultCollisionMarginData()

virtual void tesseract_collision::DiscreteContactManager::setDefaultCollisionMarginData ( double  default_collision_margin)
pure virtual

◆ setIsContactAllowedFn()

virtual void tesseract_collision::DiscreteContactManager::setIsContactAllowedFn ( IsContactAllowedFn  fn)
pure virtual

◆ setPairCollisionMarginData()

virtual void tesseract_collision::DiscreteContactManager::setPairCollisionMarginData ( 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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.


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