moveit2
The MoveIt Motion Planning Framework for ROS 2.
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]
Collaboration diagram for collision_detection_bullet::BulletBVHManager:
Collaboration graph
[legend]

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletBVHManager ()
 Constructor. More...
 
virtual ~BulletBVHManager ()
 
BulletBVHManagerPtr clone () const
 Clone the manager. 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...
 
bool enableCollisionObject (const std::string &name)
 Enable an object. More...
 
bool disableCollisionObject (const std::string &name)
 Disable an object. More...
 
void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose)
 Set a single static collision object's transform. More...
 
void setActiveCollisionObjects (const std::vector< std::string > &names)
 Set which collision objects are active. More...
 
const std::vector< std::string > & getActiveCollisionObjects () const
 Get which collision objects are active. 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...
 
double getContactDistanceThreshold () const
 Get the contact distance threshold. 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...
 
virtual void addCollisionObject (const CollisionObjectWrapperPtr &cow)=0
 Add a collision object to the checker. More...
 
const std::map< std::string, CollisionObjectWrapperPtr > & getCollisionObjects () const
 

Protected Attributes

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

Detailed Description

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

Definition at line 44 of file bullet_bvh_manager.h.

Constructor & Destructor Documentation

◆ BulletBVHManager()

collision_detection_bullet::BulletBVHManager::BulletBVHManager ( )

Constructor.

Definition at line 40 of file bullet_bvh_manager.cpp.

◆ ~BulletBVHManager()

collision_detection_bullet::BulletBVHManager::~BulletBVHManager ( )
virtual

Definition at line 58 of file bullet_bvh_manager.cpp.

Here is the call graph for this function:

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 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.

Add a tesseract collision object to the manager

Parameters
cowThe tesseract bullet collision object

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

◆ 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::BulletDiscreteBVHManager, and collision_detection_bullet::BulletCastBVHManager.

◆ 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 96 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 84 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 140 of file bullet_bvh_manager.cpp.

◆ getCollisionObjects()

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

Definition at line 163 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 158 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 65 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 70 of file bullet_bvh_manager.cpp.

Here is the call graph for this function:

◆ 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 124 of file bullet_bvh_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setCollisionObjectsTransform()

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

Set a single static collision object's transform.

Parameters
nameThe name of the object
poseThe transformation in world

Definition at line 108 of file bullet_bvh_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 145 of file bullet_bvh_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ active_

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

A list of the active collision links.

Definition at line 137 of file bullet_bvh_manager.h.

◆ broadphase_

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

The bullet broadphase interface.

Definition at line 152 of file bullet_bvh_manager.h.

◆ coll_config_

btDefaultCollisionConfiguration collision_detection_bullet::BulletBVHManager::coll_config_
protected

The bullet collision configuration.

Definition at line 149 of file bullet_bvh_manager.h.

◆ contact_distance_

double collision_detection_bullet::BulletBVHManager::contact_distance_
protected

The contact distance threshold.

Definition at line 140 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 146 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 collision algorithm.

Definition at line 143 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 155 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 134 of file bullet_bvh_manager.h.


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