|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...
#include <bullet_bvh_manager.hpp>


Public Member Functions | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | BulletBVHManager () |
| Constructor. | |
| virtual | ~BulletBVHManager () |
| BulletBVHManagerPtr | clone () const |
| Clone the manager. | |
| bool | hasCollisionObject (const std::string &name) const |
| Find if a collision object already exists. | |
| bool | removeCollisionObject (const std::string &name) |
| Remove an object from the checker. | |
| bool | enableCollisionObject (const std::string &name) |
| Enable an object. | |
| bool | disableCollisionObject (const std::string &name) |
| Disable an object. | |
| void | setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose) |
| Set a single static collision object's transform. | |
| void | setActiveCollisionObjects (const std::vector< std::string > &names) |
| Set which collision objects are active. | |
| const std::vector< std::string > & | getActiveCollisionObjects () const |
| Get which collision objects are active. | |
| 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. | |
| double | getContactDistanceThreshold () const |
| Get the contact distance threshold. | |
| 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. | |
| virtual void | addCollisionObject (const CollisionObjectWrapperPtr &cow)=0 |
| Add a collision object to the checker. | |
| const std::map< std::string, CollisionObjectWrapperPtr > & | getCollisionObjects () const |
Protected Attributes | |
| std::map< std::string, CollisionObjectWrapperPtr > | link2cow_ |
| A map of collision objects being managed. | |
| std::vector< std::string > | active_ |
| A list of the active collision links. | |
| double | contact_distance_ |
| The contact distance threshold. | |
| std::unique_ptr< btCollisionDispatcher > | dispatcher_ |
| The bullet collision dispatcher used for getting object to object collision algorithm. | |
| btDispatcherInfo | dispatch_info_ |
| The bullet collision dispatcher configuration information. | |
| btDefaultCollisionConfiguration | coll_config_ |
| The bullet collision configuration. | |
| std::unique_ptr< btBroadphaseInterface > | broadphase_ |
| The bullet broadphase interface. | |
| BroadphaseFilterCallback | filter_callback_ |
| Callback function for culling objects before a broadphase check. | |
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
Definition at line 44 of file bullet_bvh_manager.hpp.
| collision_detection_bullet::BulletBVHManager::BulletBVHManager | ( | ) |
Constructor.
Definition at line 40 of file bullet_bvh_manager.cpp.
|
virtual |
|
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.
| name | The name of the object, must be unique. |
| mask_id | User defined id which gets stored in the results structure. |
| shapes | A vector of shapes that make up the collision object. |
| shape_poses | A vector of poses for each shape, must be same length as shapes |
| shape_types | A vector of shape types for encode the collision object. If the vector is of length 1 it is used for all shapes. |
| collision_object_types | A int identifying a conversion mode for the object. (ex. convert meshes to convex hulls) |
| enabled | Indicate if the object is enabled for collision checking. |
Add a tesseract collision object to the manager
| 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 96 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 84 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 140 of file bullet_bvh_manager.cpp.
| const std::map< std::string, CollisionObjectWrapperPtr > & collision_detection_bullet::BulletBVHManager::getCollisionObjects | ( | ) | const |
Definition at line 163 of file bullet_bvh_manager.cpp.
| double collision_detection_bullet::BulletBVHManager::getContactDistanceThreshold | ( | ) | const |
Get the contact distance threshold.
Definition at line 158 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 65 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 70 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 124 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 transform.
| name | The name of the object |
| pose | The transformation in world |
Definition at line 108 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 145 of file bullet_bvh_manager.cpp.


|
protected |
A list of the active collision links.
Definition at line 137 of file bullet_bvh_manager.hpp.
|
protected |
The bullet broadphase interface.
Definition at line 152 of file bullet_bvh_manager.hpp.
|
protected |
The bullet collision configuration.
Definition at line 149 of file bullet_bvh_manager.hpp.
|
protected |
The contact distance threshold.
Definition at line 140 of file bullet_bvh_manager.hpp.
|
protected |
The bullet collision dispatcher configuration information.
Definition at line 146 of file bullet_bvh_manager.hpp.
|
protected |
The bullet collision dispatcher used for getting object to object collision algorithm.
Definition at line 143 of file bullet_bvh_manager.hpp.
|
protected |
Callback function for culling objects before a broadphase check.
Definition at line 155 of file bullet_bvh_manager.hpp.
|
protected |
A map of collision objects being managed.
Definition at line 134 of file bullet_bvh_manager.hpp.