A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...
#include <bullet_bvh_manager.h>
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... | |
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
Definition at line 73 of file bullet_bvh_manager.h.
collision_detection_bullet::BulletBVHManager::BulletBVHManager | ( | ) |
Constructor.
Definition at line 69 of file bullet_bvh_manager.cpp.
|
virtual |
Definition at line 87 of file bullet_bvh_manager.cpp.
|
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.
cow | The tesseract bullet collision object |
Implemented in collision_detection_bullet::BulletCastBVHManager, and collision_detection_bullet::BulletDiscreteBVHManager.
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.
|
pure virtual |
Perform a contact test for all objects.
collisions | The Contact results data |
req | The collision request data |
acm | The allowed collision matrix |
self | Used for indicating self collision checks |
Implemented in collision_detection_bullet::BulletCastBVHManager, and collision_detection_bullet::BulletDiscreteBVHManager.
bool collision_detection_bullet::BulletBVHManager::disableCollisionObject | ( | const std::string & | name | ) |
Disable an object.
name | The name of the object |
Definition at line 125 of file bullet_bvh_manager.cpp.
bool collision_detection_bullet::BulletBVHManager::enableCollisionObject | ( | const std::string & | name | ) |
Enable an object.
name | The name of the object |
Definition at line 113 of file bullet_bvh_manager.cpp.
const std::vector< std::string > & collision_detection_bullet::BulletBVHManager::getActiveCollisionObjects | ( | ) | const |
Get which collision objects are active.
Definition at line 169 of file bullet_bvh_manager.cpp.
const std::map< std::string, CollisionObjectWrapperPtr > & collision_detection_bullet::BulletBVHManager::getCollisionObjects | ( | ) | const |
Definition at line 192 of file bullet_bvh_manager.cpp.
double collision_detection_bullet::BulletBVHManager::getContactDistanceThreshold | ( | ) | const |
Get the contact distance threshold.
Definition at line 187 of file bullet_bvh_manager.cpp.
bool collision_detection_bullet::BulletBVHManager::hasCollisionObject | ( | const std::string & | name | ) | const |
Find if a collision object already exists.
name | The name of the collision object |
Definition at line 94 of file bullet_bvh_manager.cpp.
bool collision_detection_bullet::BulletBVHManager::removeCollisionObject | ( | const std::string & | name | ) |
Remove an object from the checker.
name | The name of the object |
Definition at line 99 of file bullet_bvh_manager.cpp.
void collision_detection_bullet::BulletBVHManager::setActiveCollisionObjects | ( | const std::vector< std::string > & | names | ) |
Set which collision objects are active.
names | A vector of collision object names |
Definition at line 153 of file bullet_bvh_manager.cpp.
void collision_detection_bullet::BulletBVHManager::setCollisionObjectsTransform | ( | const std::string & | name, |
const Eigen::Isometry3d & | pose | ||
) |
Set a single static collision object's tansform.
name | The name of the object |
pose | The tranformation in world |
Definition at line 137 of file bullet_bvh_manager.cpp.
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.
contact_distance | The contact distance |
Definition at line 174 of file bullet_bvh_manager.cpp.
|
protected |
A list of the active collision links.
Definition at line 154 of file bullet_bvh_manager.h.
|
protected |
The bullet broadphase interface.
Definition at line 169 of file bullet_bvh_manager.h.
|
protected |
The bullet collision configuration.
Definition at line 166 of file bullet_bvh_manager.h.
|
protected |
The contact distance threshold.
Definition at line 157 of file bullet_bvh_manager.h.
|
protected |
The bullet collision dispatcher configuration information.
Definition at line 163 of file bullet_bvh_manager.h.
|
protected |
The bullet collision dispatcher used for getting object to object collison algorithm.
Definition at line 160 of file bullet_bvh_manager.h.
|
protected |
Callback function for culling objects before a broadphase check.
Definition at line 172 of file bullet_bvh_manager.h.
|
protected |
A map of collision objects being managed.
Definition at line 151 of file bullet_bvh_manager.h.