Go to the documentation of this file.
41 #ifndef TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
42 #define TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
54 using Ptr = std::shared_ptr<BulletDiscreteBVHManager>;
55 using ConstPtr = std::shared_ptr<const BulletDiscreteBVHManager>;
56 using UPtr = std::unique_ptr<BulletDiscreteBVHManager>;
57 using ConstUPtr = std::unique_ptr<const BulletDiscreteBVHManager>;
67 std::string
getName() const override final;
75 bool enabled = true) override final;
116 const std::
string& name2,
117 double collision_margin) override final;
167 #endif // TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
std::string getName() const override final
Get the name of the contact manager.
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
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.
Modified bullet collision configuration.
ContactTestData contact_test_data_
This is used when contactTest is called. It is also added as a user point to the collsion objects so ...
This is a modified configuration that included the modified Bullet algorithms.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
This class is used to filter broadphase.
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.
DiscreteContactManager::UPtr clone() const override final
Clone the manager.
TesseractCollisionConfiguration coll_config_
The bullet collision configuration.
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
std::unique_ptr< BulletDiscreteBVHManager > UPtr
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
BulletDiscreteBVHManager & operator=(const BulletDiscreteBVHManager &)=delete
std::map< std::string, COW::Ptr > Link2Cow
bool disableCollisionObject(const std::string &name) override final
Disable an object.
void setDefaultCollisionMargin(double default_collision_margin) override final
Set the default collision margin.
TesseractCollisionConfigurationInfo config_info_
The bullet collision configuration information.
CollisionMarginPairOverrideType
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
Tesseract ROS Bullet environment utility function.
This is a tesseract bullet collsion object.
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
Link2Cow link2cow_
A map of all (static and active) collision objects being managed.
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single collision object's transforms.
bool enableCollisionObject(const std::string &name) override final
Enable an object.
std::vector< CollisionShapeConstPtr > CollisionShapesConst
std::shared_ptr< BulletDiscreteBVHManager > Ptr
std::vector< std::string > collision_objects_
A list of the collision objects.
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.
std::shared_ptr< const BulletDiscreteBVHManager > ConstPtr
TesseractOverlapFilterCallback broadphase_overlap_cb_
Filter collision objects before broadphase check.
std::unique_ptr< const BulletDiscreteBVHManager > ConstUPtr
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
std::vector< std::string > active_
A list of the active collision objects.
A BVH implementation of a bullet manager.
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.
~BulletDiscreteBVHManager() override
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
BulletDiscreteBVHManager(std::string name="BulletDiscreteBVHManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
void incrementCollisionMargin(double increment) override final
Increment the collision margin data by some value.
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.
void setCollisionMarginPair(const std::string &name1, const std::string &name2, double collision_margin) override final
Set the margin for a given contact pair.
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
void setCollisionMarginData(CollisionMarginData collision_margin_data) override final
Set the contact distance threshold.