Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
bullet_discrete_bvh_manager.h
Go to the documentation of this file.
1
41#ifndef TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
42#define TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
43
47
49{
52{
53public:
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>;
58
59 BulletDiscreteBVHManager(std::string name = "BulletDiscreteBVHManager",
66
67 std::string getName() const override final;
68
69 DiscreteContactManager::UPtr clone() const override final;
70
71 bool addCollisionObject(const std::string& name,
72 const int& mask_id,
73 const CollisionShapesConst& shapes,
74 const tesseract_common::VectorIsometry3d& shape_poses,
75 bool enabled = true) override final;
76
77 const CollisionShapesConst& getCollisionObjectGeometries(const std::string& name) const override final;
78
79 const tesseract_common::VectorIsometry3d&
80 getCollisionObjectGeometriesTransforms(const std::string& name) const override final;
81
82 bool hasCollisionObject(const std::string& name) const override final;
83
84 bool removeCollisionObject(const std::string& name) override final;
85
86 bool enableCollisionObject(const std::string& name) override final;
87
88 bool disableCollisionObject(const std::string& name) override final;
89
90 bool isCollisionObjectEnabled(const std::string& name) const override final;
91
92 void setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose) override final;
93
94 void setCollisionObjectsTransform(const std::vector<std::string>& names,
95 const tesseract_common::VectorIsometry3d& poses) override final;
96
97 void setCollisionObjectsTransform(const tesseract_common::TransformMap& transforms) override final;
98
99 const std::vector<std::string>& getCollisionObjects() const override final;
100
101 void setActiveCollisionObjects(const std::vector<std::string>& names) override final;
102
103 const std::vector<std::string>& getActiveCollisionObjects() const override final;
104
106 CollisionMarginData collision_margin_data,
107 CollisionMarginOverrideType override_type = CollisionMarginOverrideType::REPLACE) override final;
108
109 void setDefaultCollisionMarginData(double default_collision_margin) override final;
110
111 void setPairCollisionMarginData(const std::string& name1,
112 const std::string& name2,
113 double collision_margin) override final;
114
115 const CollisionMarginData& getCollisionMarginData() const override final;
116
117 void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
118
119 IsContactAllowedFn getIsContactAllowedFn() const override final;
120
121 void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;
122
127 void addCollisionObject(const COW::Ptr& cow);
128
129private:
130 std::string name_;
132 std::vector<std::string> active_;
134 std::vector<std::string> collision_objects_;
136 std::unique_ptr<btCollisionDispatcher> dispatcher_;
138 btDispatcherInfo dispatch_info_;
144 std::unique_ptr<btBroadphaseInterface> broadphase_;
147
153
156
159};
160
161} // namespace tesseract_collision::tesseract_collision_bullet
162#endif // TESSERACT_COLLISION_BULLET_DISCRETE_BVH_MANAGERS_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Tesseract ROS Bullet environment utility function.
This structure hold contact results for link pairs.
Definition: types.h:154
Definition: discrete_contact_manager.h:41
A BVH implementation of a bullet manager.
Definition: bullet_discrete_bvh_manager.h:52
~BulletDiscreteBVHManager() override
Definition: bullet_discrete_bvh_manager.cpp:73
std::vector< std::string > collision_objects_
A list of the collision objects.
Definition: bullet_discrete_bvh_manager.h:134
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
Definition: bullet_discrete_bvh_manager.cpp:277
bool enableCollisionObject(const std::string &name) override final
Enable an object.
Definition: bullet_discrete_bvh_manager.cpp:163
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
Definition: bullet_discrete_bvh_manager.h:138
TesseractCollisionConfiguration coll_config_
The bullet collision configuration.
Definition: bullet_discrete_bvh_manager.h:142
void setIsContactAllowedFn(IsContactAllowedFn fn) override final
Set the active function for determining if two links are allowed to be in collision.
Definition: bullet_discrete_bvh_manager.cpp:275
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
Definition: bullet_discrete_bvh_manager.cpp:144
IsContactAllowedFn getIsContactAllowedFn() const override final
Get the active function for determining if two links are allowed to be in collision.
Definition: bullet_discrete_bvh_manager.cpp:276
TesseractOverlapFilterCallback broadphase_overlap_cb_
Filter collision objects before broadphase check.
Definition: bullet_discrete_bvh_manager.h:155
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
Definition: bullet_discrete_bvh_manager.cpp:149
void setCollisionMarginData(CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE) override final
Set the contact distance thresholds for which collision should be considered on a per pair basis.
Definition: bullet_discrete_bvh_manager.cpp:250
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
Definition: bullet_discrete_bvh_manager.cpp:249
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
Definition: bullet_discrete_bvh_manager.cpp:305
TesseractCollisionConfigurationInfo config_info_
The bullet collision configuration information.
Definition: bullet_discrete_bvh_manager.h:140
BulletDiscreteBVHManager & operator=(const BulletDiscreteBVHManager &)=delete
std::shared_ptr< const BulletDiscreteBVHManager > ConstPtr
Definition: bullet_discrete_bvh_manager.h:55
std::unique_ptr< const BulletDiscreteBVHManager > ConstUPtr
Definition: bullet_discrete_bvh_manager.h:57
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
Definition: bullet_discrete_bvh_manager.cpp:233
void setDefaultCollisionMarginData(double default_collision_margin) override final
Set the default collision margin.
Definition: bullet_discrete_bvh_manager.cpp:257
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
Definition: bullet_discrete_bvh_manager.cpp:235
std::unique_ptr< BulletDiscreteBVHManager > UPtr
Definition: bullet_discrete_bvh_manager.h:56
std::string getName() const override final
Get the name of the contact manager.
Definition: bullet_discrete_bvh_manager.cpp:80
std::vector< std::string > active_
A list of the active collision objects.
Definition: bullet_discrete_bvh_manager.h:132
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.
Definition: bullet_discrete_bvh_manager.cpp:129
BulletDiscreteBVHManager & operator=(BulletDiscreteBVHManager &&)=delete
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
Definition: bullet_discrete_bvh_manager.cpp:195
std::string name_
Definition: bullet_discrete_bvh_manager.h:130
bool disableCollisionObject(const std::string &name) override final
Disable an object.
Definition: bullet_discrete_bvh_manager.cpp:179
DiscreteContactManager::UPtr clone() const override final
Clone the manager.
Definition: bullet_discrete_bvh_manager.cpp:82
void setPairCollisionMarginData(const std::string &name1, const std::string &name2, double collision_margin) override final
Set the margin for a given contact pair.
Definition: bullet_discrete_bvh_manager.cpp:263
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collison algorithm.
Definition: bullet_discrete_bvh_manager.h:136
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
Definition: bullet_discrete_bvh_manager.cpp:137
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
Definition: bullet_discrete_bvh_manager.h:144
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
Definition: bullet_discrete_bvh_manager.cpp:271
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single collision object's transforms.
Definition: bullet_discrete_bvh_manager.cpp:204
ContactTestData contact_test_data_
This is used when contactTest is called. It is also added as a user point to the collsion objects so ...
Definition: bullet_discrete_bvh_manager.h:152
std::shared_ptr< BulletDiscreteBVHManager > Ptr
Definition: bullet_discrete_bvh_manager.h:54
Link2Cow link2cow_
A map of all (static and active) collision objects being managed.
Definition: bullet_discrete_bvh_manager.h:146
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.
Definition: bullet_discrete_bvh_manager.cpp:108
This is a tesseract bullet collsion object.
Definition: bullet_utils.h:89
This is a modified configuration that included the modified Bullet algorithms.
Definition: tesseract_collision_configuration.h:82
This class is used to filter broadphase.
Definition: bullet_utils.h:349
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:74
This is the discrete contact manager base class.
Definition: bullet_cast_bvh_manager.h:49
std::map< std::string, COW::Ptr > Link2Cow
Definition: bullet_utils.h:150
std::vector< tesseract_geometry::Geometry::ConstPtr > CollisionShapesConst
Definition: types.h:47
std::function< bool(const std::string &, const std::string &)> IsContactAllowedFn
Should return true if contact allowed, otherwise false.
Definition: types.h:59
Definition: allowed_collision_matrix.h:16
CollisionMarginOverrideType
Identifies how the provided contact margin data should be applied.
Definition: collision_margin_data.h:46
The ContactRequest struct.
Definition: types.h:294
This data is intended only to be used internal to the collision checkers as a container and should no...
Definition: types.h:319
Modified bullet collision configuration.
auto pose
Definition: tesseract_environment_collision.cpp:118