A BVH implementation of a bullet manager. More...
#include <bullet_discrete_bvh_manager.h>

Public Types | |
| using | ConstPtr = std::shared_ptr< const BulletDiscreteBVHManager > |
| using | ConstUPtr = std::unique_ptr< const BulletDiscreteBVHManager > |
| using | Ptr = std::shared_ptr< BulletDiscreteBVHManager > |
| using | UPtr = std::unique_ptr< BulletDiscreteBVHManager > |
Public Types inherited from tesseract_collision::DiscreteContactManager | |
| using | ConstPtr = std::shared_ptr< const DiscreteContactManager > |
| using | ConstUPtr = std::unique_ptr< const DiscreteContactManager > |
| using | Ptr = std::shared_ptr< DiscreteContactManager > |
| using | UPtr = std::unique_ptr< DiscreteContactManager > |
Public Member Functions | |
| void | addCollisionObject (const COW::Ptr &cow) |
| A a bullet collision object to the manager. More... | |
| bool | addCollisionObject (const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true) override final |
| Add a object to the checker. More... | |
| BulletDiscreteBVHManager (BulletDiscreteBVHManager &&)=delete | |
| BulletDiscreteBVHManager (const BulletDiscreteBVHManager &)=delete | |
| BulletDiscreteBVHManager (std::string name="BulletDiscreteBVHManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo()) | |
| DiscreteContactManager::UPtr | clone () const override final |
| Clone the manager. More... | |
| void | contactTest (ContactResultMap &collisions, const ContactRequest &request) override final |
| Perform a contact test for all objects based. More... | |
| bool | disableCollisionObject (const std::string &name) override final |
| Disable an object. More... | |
| bool | enableCollisionObject (const std::string &name) override final |
| Enable an object. More... | |
| const std::vector< std::string > & | getActiveCollisionObjects () const override final |
| Get which collision objects can move. More... | |
| const CollisionMarginData & | getCollisionMarginData () const override final |
| Get the contact distance threshold. More... | |
| const CollisionShapesConst & | getCollisionObjectGeometries (const std::string &name) const override final |
| Get a collision objects collision geometries. More... | |
| const tesseract_common::VectorIsometry3d & | getCollisionObjectGeometriesTransforms (const std::string &name) const override final |
| Get a collision objects collision geometries transforms. More... | |
| const std::vector< std::string > & | getCollisionObjects () const override final |
| Get all collision objects. More... | |
| std::shared_ptr< const tesseract_common::ContactAllowedValidator > | getContactAllowedValidator () const override final |
| Get the active function for determining if two links are allowed to be in collision. More... | |
| std::string | getName () const override final |
| Get the name of the contact manager. More... | |
| bool | hasCollisionObject (const std::string &name) const override final |
| Find if a collision object already exists. More... | |
| void | incrementCollisionMargin (double increment) override final |
| Increment the collision margin data by some value. More... | |
| bool | isCollisionObjectEnabled (const std::string &name) const override final |
| Check if collision object is enabled. More... | |
| BulletDiscreteBVHManager & | operator= (BulletDiscreteBVHManager &&)=delete |
| BulletDiscreteBVHManager & | operator= (const BulletDiscreteBVHManager &)=delete |
| bool | removeCollisionObject (const std::string &name) override final |
| Remove an object from the checker. More... | |
| void | setActiveCollisionObjects (const std::vector< std::string > &names) override final |
| Set which collision objects can move. More... | |
| void | setCollisionMarginData (CollisionMarginData collision_margin_data) override final |
| Set the contact distance threshold. More... | |
| void | setCollisionMarginPair (const std::string &name1, const std::string &name2, double collision_margin) override final |
| Set the margin for a given contact pair. More... | |
| void | setCollisionMarginPairData (const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE) override final |
| Set the contact distance thresholds for which collision should be considered on a per pair basis. More... | |
| void | setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose) override final |
| Set a single collision object's transforms. More... | |
| void | setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses) override final |
| Set a series of collision object's transforms. More... | |
| void | setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms) override final |
| Set a series of collision object's transforms. More... | |
| void | setContactAllowedValidator (std::shared_ptr< const tesseract_common::ContactAllowedValidator > validator) override final |
| Set the active function for determining if two links are allowed to be in collision. More... | |
| void | setDefaultCollisionMargin (double default_collision_margin) override final |
| Set the default collision margin. More... | |
| ~BulletDiscreteBVHManager () override | |
Public Member Functions inherited from tesseract_collision::DiscreteContactManager | |
| virtual void | applyContactManagerConfig (const ContactManagerConfig &config) |
| Applies settings in the config. More... | |
| DiscreteContactManager ()=default | |
| DiscreteContactManager (const DiscreteContactManager &)=delete | |
| DiscreteContactManager (DiscreteContactManager &&)=delete | |
| DiscreteContactManager & | operator= (const DiscreteContactManager &)=delete |
| DiscreteContactManager & | operator= (DiscreteContactManager &&)=delete |
| virtual | ~DiscreteContactManager ()=default |
Private Member Functions | |
| void | onCollisionMarginDataChanged () |
| This function will update internal data when margin data has changed. More... | |
Private Attributes | |
| std::vector< std::string > | active_ |
| A list of the active collision objects. More... | |
| std::unique_ptr< btBroadphaseInterface > | broadphase_ |
| The bullet broadphase interface. More... | |
| TesseractOverlapFilterCallback | broadphase_overlap_cb_ |
| Filter collision objects before broadphase check. More... | |
| TesseractCollisionConfiguration | coll_config_ |
| The bullet collision configuration. More... | |
| std::vector< std::string > | collision_objects_ |
| A list of the collision objects. More... | |
| TesseractCollisionConfigurationInfo | config_info_ |
| The bullet collision configuration information. More... | |
| ContactTestData | contact_test_data_ |
| This is used when contactTest is called. It is also added as a user point to the collsion objects so it can be used to exit collision checking for compound shapes. 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... | |
| Link2Cow | link2cow_ |
| A map of all (static and active) collision objects being managed. More... | |
| std::string | name_ |
A BVH implementation of a bullet manager.
Definition at line 51 of file bullet_discrete_bvh_manager.h.
| using tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::ConstPtr = std::shared_ptr<const BulletDiscreteBVHManager> |
Definition at line 55 of file bullet_discrete_bvh_manager.h.
| using tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::ConstUPtr = std::unique_ptr<const BulletDiscreteBVHManager> |
Definition at line 57 of file bullet_discrete_bvh_manager.h.
| using tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::Ptr = std::shared_ptr<BulletDiscreteBVHManager> |
Definition at line 54 of file bullet_discrete_bvh_manager.h.
| using tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::UPtr = std::unique_ptr<BulletDiscreteBVHManager> |
Definition at line 56 of file bullet_discrete_bvh_manager.h.
| tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::BulletDiscreteBVHManager | ( | std::string | name = "BulletDiscreteBVHManager", |
| TesseractCollisionConfigurationInfo | config_info = TesseractCollisionConfigurationInfo() |
||
| ) |
Definition at line 52 of file bullet_discrete_bvh_manager.cpp.
|
override |
Definition at line 74 of file bullet_discrete_bvh_manager.cpp.
|
delete |
|
delete |
| void tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::addCollisionObject | ( | const COW::Ptr & | cow | ) |
A a bullet collision object to the manager.
| cow | The tesseract bullet collision object |
Definition at line 318 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Add a object to the checker.
| 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 |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 109 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Clone the manager.
This is to be used for multi threaded application. A user should make a clone for each thread.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 83 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Perform a contact test for all objects based.
| collisions | The contact results data |
| request | The contact request data |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 300 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Disable an object.
| name | The name of the object |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 180 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Enable an object.
| name | The name of the object |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 164 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get which collision objects can move.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 250 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get the contact distance threshold.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 258 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get a collision objects collision geometries.
| name | The collision objects name |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 130 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get a collision objects collision geometries transforms.
| name | The collision objects name |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 138 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get all collision objects.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 234 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get the active function for determining if two links are allowed to be in collision.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 296 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Get the name of the contact manager.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 81 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Find if a collision object already exists.
| name | The name of the collision object |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 145 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Increment the collision margin data by some value.
| increment | The value to increment the collision margin value |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 284 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Check if collision object is enabled.
| name | The name of the object |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 196 of file bullet_discrete_bvh_manager.cpp.
|
private |
This function will update internal data when margin data has changed.
Definition at line 328 of file bullet_discrete_bvh_manager.cpp.
|
delete |
|
delete |
|
finaloverridevirtual |
Remove an object from the checker.
| name | The name of the object |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 150 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set which collision objects can move.
| names | A vector of collision object names |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 236 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set the contact distance threshold.
| collision_margin_data | The contact distance |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 252 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set the margin for a given contact pair.
The order of the object names does not matter, that is handled internal to the class.
| obj1 | The first object name. Order doesn't matter |
| obj2 | The Second object name. Order doesn't matter |
| collision_margin | contacts with distance < collision_margin are considered in collision |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 276 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set the contact distance thresholds for which collision should be considered on a per pair basis.
| pair_margin_data | Contains the pair collision margins that will replace the current settings |
| override_type | This determines how the provided CollisionMarginData is applied |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 263 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set a single collision object's transforms.
| name | The name of the object |
| pose | The transformation in world |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 205 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set a series of collision object's transforms.
| names | The name of the object |
| poses | The transformation in world |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 220 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set a series of collision object's transforms.
| transforms | A transform map <name, pose> |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 228 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set the active function for determining if two links are allowed to be in collision.
Implements tesseract_collision::DiscreteContactManager.
Definition at line 290 of file bullet_discrete_bvh_manager.cpp.
|
finaloverridevirtual |
Set the default collision margin.
| default_collision_margin | New default collision margin |
Implements tesseract_collision::DiscreteContactManager.
Definition at line 270 of file bullet_discrete_bvh_manager.cpp.
|
private |
A list of the active collision objects.
Definition at line 137 of file bullet_discrete_bvh_manager.h.
|
private |
The bullet broadphase interface.
Definition at line 149 of file bullet_discrete_bvh_manager.h.
|
private |
Filter collision objects before broadphase check.
Definition at line 160 of file bullet_discrete_bvh_manager.h.
|
private |
The bullet collision configuration.
Definition at line 147 of file bullet_discrete_bvh_manager.h.
|
private |
A list of the collision objects.
Definition at line 139 of file bullet_discrete_bvh_manager.h.
|
private |
The bullet collision configuration information.
Definition at line 145 of file bullet_discrete_bvh_manager.h.
|
private |
This is used when contactTest is called. It is also added as a user point to the collsion objects so it can be used to exit collision checking for compound shapes.
Definition at line 157 of file bullet_discrete_bvh_manager.h.
|
private |
The bullet collision dispatcher configuration information.
Definition at line 143 of file bullet_discrete_bvh_manager.h.
|
private |
The bullet collision dispatcher used for getting object to object collison algorithm.
Definition at line 141 of file bullet_discrete_bvh_manager.h.
|
private |
A map of all (static and active) collision objects being managed.
Definition at line 151 of file bullet_discrete_bvh_manager.h.
|
private |
Definition at line 135 of file bullet_discrete_bvh_manager.h.