moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
collision_detection_bullet::BulletCastBVHManager Class Reference

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

#include <bullet_cast_bvh_manager.h>

Inheritance diagram for collision_detection_bullet::BulletCastBVHManager:
Inheritance graph
[legend]
Collaboration diagram for collision_detection_bullet::BulletCastBVHManager:
Collaboration graph
[legend]

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW BulletCastBVHManager ()=default
 Constructor. More...
 
 ~BulletCastBVHManager () override=default
 
BulletCastBVHManagerPtr clone () const
 Clone the manager. More...
 
void setCastCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
 Set a single cast (moving) collision object's transforms. 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. More...
 
void addCollisionObject (const CollisionObjectWrapperPtr &cow) override
 Add a tesseract collision object to the manager. More...
 
- Public Member Functions inherited from collision_detection_bullet::BulletBVHManager
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...
 
const std::map< std::string, CollisionObjectWrapperPtr > & getCollisionObjects () const
 

Additional Inherited Members

- Protected Attributes inherited from collision_detection_bullet::BulletBVHManager
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 45 of file bullet_cast_bvh_manager.h.

Constructor & Destructor Documentation

◆ BulletCastBVHManager()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW collision_detection_bullet::BulletCastBVHManager::BulletCastBVHManager ( )
default

Constructor.

◆ ~BulletCastBVHManager()

collision_detection_bullet::BulletCastBVHManager::~BulletCastBVHManager ( )
overridedefault

Member Function Documentation

◆ addCollisionObject()

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

Add a tesseract collision object to the manager.

Parameters
cowThe tesseract bullet collision object

Implements collision_detection_bullet::BulletBVHManager.

Definition at line 151 of file bullet_cast_bvh_manager.cpp.

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

◆ clone()

BulletCastBVHManagerPtr collision_detection_bullet::BulletCastBVHManager::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 44 of file bullet_cast_bvh_manager.cpp.

◆ contactTest()

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

Perform a contact test for all objects.

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

Implements collision_detection_bullet::BulletBVHManager.

Definition at line 136 of file bullet_cast_bvh_manager.cpp.

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

◆ setCastCollisionObjectsTransform()

void collision_detection_bullet::BulletCastBVHManager::setCastCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose1,
const Eigen::Isometry3d &  pose2 
)

Set a single cast (moving) collision object's transforms.

This should only be used for moving objects.

Parameters
nameThe name of the object
pose1The start transformation in world
pose2The end transformation in world

Definition at line 66 of file bullet_cast_bvh_manager.cpp.

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

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