Tesseract
Motion Planning Environment
|
#include <discrete_contact_manager.h>
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 | |
DiscreteContactManager & | operator= (const DiscreteContactManager &)=delete |
DiscreteContactManager (DiscreteContactManager &&)=delete | |
DiscreteContactManager & | operator= (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 CollisionShapesConst & | getCollisionObjectGeometries (const std::string &name) const =0 |
Get a collision objects collision geometries. More... | |
virtual const tesseract_common::VectorIsometry3d & | getCollisionObjectGeometriesTransforms (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 CollisionMarginData & | getCollisionMarginData () 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... | |
using tesseract_collision::DiscreteContactManager::ConstPtr = std::shared_ptr<const DiscreteContactManager> |
using tesseract_collision::DiscreteContactManager::ConstUPtr = std::unique_ptr<const DiscreteContactManager> |
using tesseract_collision::DiscreteContactManager::Ptr = std::shared_ptr<DiscreteContactManager> |
using tesseract_collision::DiscreteContactManager::UPtr = std::unique_ptr<DiscreteContactManager> |
|
default |
|
virtualdefault |
|
delete |
|
delete |
|
pure virtual |
Add a object to the checker.
name | The name of the object, must be unique. |
mask_id | User defined id which gets stored in the results structure. |
shapes | A vector of shapes that make up the collision object. |
shape_poses | A vector of poses for each shape, must be same length as shapes |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
virtual |
Applies settings in the config.
config | Settings to be applies |
|
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::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Perform a contact test for all objects based.
collisions | The contact results data |
request | The contact request data |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Disable an object.
name | The name of the object |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Enable an object.
name | The name of the object |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get which collision objects can move.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get the contact distance threshold.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get a collision objects collision geometries.
name | The collision objects name |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get a collision objects collision geometries transforms.
name | The collision objects name |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get all collision objects.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get the active function for determining if two links are allowed to be in collision.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Get the name of the contact manager.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Find if a collision object already exists.
name | The name of the collision object |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Check if collision object is enabled.
name | The name of the object |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
delete |
|
delete |
|
pure virtual |
Remove an object from the checker.
name | The name of the object |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set which collision objects can move.
names | A vector of collision object names |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set the contact distance thresholds for which collision should be considered on a per pair basis.
collision_margin_data | Contains the data that will replace the current settings |
override_type | This 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.
|
pure virtual |
Set a single collision object's transforms.
name | The name of the object |
pose | The transformation in world |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set a series of collision object's transforms.
names | The name of the object |
poses | The transformation in world |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set a series of collision object's transforms.
transforms | A transform map <name, pose> |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set the default collision margin.
default_collision_margin | New default collision margin |
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
pure virtual |
Set the active function for determining if two links are allowed to be in collision.
Implemented in tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager, tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager, and tesseract_collision::tesseract_collision_fcl::FCLDiscreteBVHManager.
|
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.
obj1 | The first object name. Order doesn't matter |
obj2 | The Second object name. Order doesn't matter |
collision_margin | contacts 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.