Public Member Functions | List of all members
collision_detection_bullet::BulletDiscreteBVHManager Class Reference

A bounding volume hierarchy (BVH) implementaiton of a discrete bullet manager. More...

#include <bullet_discrete_bvh_manager.h>

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

Public Member Functions

void addCollisionObject (const CollisionObjectWrapperPtr &cow) override
 Add a bullet collision object to the manager. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletDiscreteBVHManager ()=default
 Constructor. More...
 
BulletDiscreteBVHManagerPtr clone () const
 Clone the manager. More...
 
void contactTest (collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
 Perform a contact test for all objects in the manager. More...
 
 ~BulletDiscreteBVHManager () override=default
 
- Public Member Functions inherited from collision_detection_bullet::BulletBVHManager
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletBVHManager ()
 Constructor. More...
 
BulletBVHManagerPtr clone () const
 Clone the manager. 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 ()
 

Additional Inherited Members

- Protected Attributes inherited from collision_detection_bullet::BulletBVHManager
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) implementaiton of a discrete bullet manager.

Definition at line 74 of file bullet_discrete_bvh_manager.h.

Constructor & Destructor Documentation

◆ BulletDiscreteBVHManager()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW collision_detection_bullet::BulletDiscreteBVHManager::BulletDiscreteBVHManager ( )
default

Constructor.

◆ ~BulletDiscreteBVHManager()

collision_detection_bullet::BulletDiscreteBVHManager::~BulletDiscreteBVHManager ( )
overridedefault

Member Function Documentation

◆ addCollisionObject()

void collision_detection_bullet::BulletDiscreteBVHManager::addCollisionObject ( const CollisionObjectWrapperPtr &  cow)
overridevirtual

Add a bullet collision object to the manager.

Parameters
cowThe bullet collision object

Implements collision_detection_bullet::BulletBVHManager.

Definition at line 110 of file bullet_discrete_bvh_manager.cpp.

◆ clone()

BulletDiscreteBVHManagerPtr collision_detection_bullet::BulletDiscreteBVHManager::clone ( ) const

Clone the manager.

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

Definition at line 67 of file bullet_discrete_bvh_manager.cpp.

◆ contactTest()

void collision_detection_bullet::BulletDiscreteBVHManager::contactTest ( collision_detection::CollisionResult collisions,
const collision_detection::CollisionRequest req,
const collision_detection::AllowedCollisionMatrix acm,
bool  self 
)
overridevirtual

Perform a contact test for all objects in the manager.

Parameters
collisionsThe Contact results data
acmThe allowed collision matrix
reqThe contact request

Implements collision_detection_bullet::BulletBVHManager.

Definition at line 89 of file bullet_discrete_bvh_manager.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:42