Public Member Functions | Protected Attributes | List of all members
collision_detection_bullet::BulletBVHManager Class Referenceabstract

A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...

#include <bullet_bvh_manager.h>

Inheritance diagram for collision_detection_bullet::BulletBVHManager:
Inheritance graph
[legend]

Public Member Functions

virtual void addCollisionObject (const CollisionObjectWrapperPtr &cow)=0
 Add a collision object to the checker. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletBVHManager ()
 Constructor. More...
 
BulletBVHManagerPtr clone () const
 Clone the manager. More...
 
virtual void contactTest (collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self)=0
 Perform a contact test for all objects. More...
 
bool disableCollisionObject (const std::string &name)
 Disable an object. More...
 
bool enableCollisionObject (const std::string &name)
 Enable an object. More...
 
const std::vector< std::string > & getActiveCollisionObjects () const
 Get which collision objects are active. More...
 
const std::map< std::string, CollisionObjectWrapperPtr > & getCollisionObjects () const
 
double getContactDistanceThreshold () const
 Get the contact distance threshold. More...
 
bool hasCollisionObject (const std::string &name) const
 Find if a collision object already exists. More...
 
bool removeCollisionObject (const std::string &name)
 Remove an object from the checker. More...
 
void setActiveCollisionObjects (const std::vector< std::string > &names)
 Set which collision objects are active. More...
 
void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose)
 Set a single static collision object's tansform. More...
 
void setContactDistanceThreshold (double contact_distance)
 Set the contact distance threshold for which collision should be considered through expanding the AABB by the contact_distance for all links. More...
 
virtual ~BulletBVHManager ()
 

Protected Attributes

std::vector< std::string > active_
 A list of the active collision links. More...
 
std::unique_ptr< btBroadphaseInterface > broadphase_
 The bullet broadphase interface. More...
 
btDefaultCollisionConfiguration coll_config_
 The bullet collision configuration. More...
 
double contact_distance_
 The contact distance threshold. More...
 
btDispatcherInfo dispatch_info_
 The bullet collision dispatcher configuration information. More...
 
std::unique_ptr< btCollisionDispatcher > dispatcher_
 The bullet collision dispatcher used for getting object to object collison algorithm. More...
 
BroadphaseFilterCallback filter_callback_
 Callback function for culling objects before a broadphase check. More...
 
std::map< std::string, CollisionObjectWrapperPtr > link2cow_
 A map of collision objects being managed. More...
 

Detailed Description

A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.

Definition at line 73 of file bullet_bvh_manager.h.

Constructor & Destructor Documentation

◆ BulletBVHManager()

collision_detection_bullet::BulletBVHManager::BulletBVHManager ( )

Constructor.

Definition at line 69 of file bullet_bvh_manager.cpp.

◆ ~BulletBVHManager()

collision_detection_bullet::BulletBVHManager::~BulletBVHManager ( )
virtual

Definition at line 87 of file bullet_bvh_manager.cpp.

Member Function Documentation

◆ addCollisionObject()

virtual void collision_detection_bullet::BulletBVHManager::addCollisionObject ( const CollisionObjectWrapperPtr &  cow)
pure virtual

Add a collision object to the checker.

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

Parameters
cowThe tesseract bullet collision object

Implemented in collision_detection_bullet::BulletCastBVHManager, and collision_detection_bullet::BulletDiscreteBVHManager.

◆ clone()

BulletBVHManagerPtr collision_detection_bullet::BulletBVHManager::clone ( ) const

Clone the manager.

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

◆ contactTest()

virtual void collision_detection_bullet::BulletBVHManager::contactTest ( collision_detection::CollisionResult collisions,
const collision_detection::CollisionRequest req,
const collision_detection::AllowedCollisionMatrix acm,
bool  self 
)
pure virtual

Perform a contact test for all objects.

Parameters
collisionsThe Contact results data
reqThe collision request data
acmThe allowed collision matrix
selfUsed for indicating self collision checks

Implemented in collision_detection_bullet::BulletCastBVHManager, and collision_detection_bullet::BulletDiscreteBVHManager.

◆ disableCollisionObject()

bool collision_detection_bullet::BulletBVHManager::disableCollisionObject ( const std::string &  name)

Disable an object.

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

Definition at line 125 of file bullet_bvh_manager.cpp.

◆ enableCollisionObject()

bool collision_detection_bullet::BulletBVHManager::enableCollisionObject ( const std::string &  name)

Enable an object.

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

Definition at line 113 of file bullet_bvh_manager.cpp.

◆ getActiveCollisionObjects()

const std::vector< std::string > & collision_detection_bullet::BulletBVHManager::getActiveCollisionObjects ( ) const

Get which collision objects are active.

Returns
A vector of collision object names

Definition at line 169 of file bullet_bvh_manager.cpp.

◆ getCollisionObjects()

const std::map< std::string, CollisionObjectWrapperPtr > & collision_detection_bullet::BulletBVHManager::getCollisionObjects ( ) const

Definition at line 192 of file bullet_bvh_manager.cpp.

◆ getContactDistanceThreshold()

double collision_detection_bullet::BulletBVHManager::getContactDistanceThreshold ( ) const

Get the contact distance threshold.

Returns
The contact distance

Definition at line 187 of file bullet_bvh_manager.cpp.

◆ hasCollisionObject()

bool collision_detection_bullet::BulletBVHManager::hasCollisionObject ( const std::string &  name) const

Find if a collision object already exists.

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

Definition at line 94 of file bullet_bvh_manager.cpp.

◆ removeCollisionObject()

bool collision_detection_bullet::BulletBVHManager::removeCollisionObject ( const std::string &  name)

Remove an object from the checker.

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

Definition at line 99 of file bullet_bvh_manager.cpp.

◆ setActiveCollisionObjects()

void collision_detection_bullet::BulletBVHManager::setActiveCollisionObjects ( const std::vector< std::string > &  names)

Set which collision objects are active.

Parameters
namesA vector of collision object names

Definition at line 153 of file bullet_bvh_manager.cpp.

◆ setCollisionObjectsTransform()

void collision_detection_bullet::BulletBVHManager::setCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose 
)

Set a single static collision object's tansform.

Parameters
nameThe name of the object
poseThe tranformation in world

Definition at line 137 of file bullet_bvh_manager.cpp.

◆ setContactDistanceThreshold()

void collision_detection_bullet::BulletBVHManager::setContactDistanceThreshold ( double  contact_distance)

Set the contact distance threshold for which collision should be considered through expanding the AABB by the contact_distance for all links.

Parameters
contact_distanceThe contact distance

Definition at line 174 of file bullet_bvh_manager.cpp.

Member Data Documentation

◆ active_

std::vector<std::string> collision_detection_bullet::BulletBVHManager::active_
protected

A list of the active collision links.

Definition at line 154 of file bullet_bvh_manager.h.

◆ broadphase_

std::unique_ptr<btBroadphaseInterface> collision_detection_bullet::BulletBVHManager::broadphase_
protected

The bullet broadphase interface.

Definition at line 169 of file bullet_bvh_manager.h.

◆ coll_config_

btDefaultCollisionConfiguration collision_detection_bullet::BulletBVHManager::coll_config_
protected

The bullet collision configuration.

Definition at line 166 of file bullet_bvh_manager.h.

◆ contact_distance_

double collision_detection_bullet::BulletBVHManager::contact_distance_
protected

The contact distance threshold.

Definition at line 157 of file bullet_bvh_manager.h.

◆ dispatch_info_

btDispatcherInfo collision_detection_bullet::BulletBVHManager::dispatch_info_
protected

The bullet collision dispatcher configuration information.

Definition at line 163 of file bullet_bvh_manager.h.

◆ dispatcher_

std::unique_ptr<btCollisionDispatcher> collision_detection_bullet::BulletBVHManager::dispatcher_
protected

The bullet collision dispatcher used for getting object to object collison algorithm.

Definition at line 160 of file bullet_bvh_manager.h.

◆ filter_callback_

BroadphaseFilterCallback collision_detection_bullet::BulletBVHManager::filter_callback_
protected

Callback function for culling objects before a broadphase check.

Definition at line 172 of file bullet_bvh_manager.h.

◆ link2cow_

std::map<std::string, CollisionObjectWrapperPtr> collision_detection_bullet::BulletBVHManager::link2cow_
protected

A map of collision objects being managed.

Definition at line 151 of file bullet_bvh_manager.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:26