Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
bullet_utils.h
Go to the documentation of this file.
1
43#ifndef TESSERACT_COLLISION_BULLET_UTILS_H
44#define TESSERACT_COLLISION_BULLET_UTILS_H
45
48#include <BulletCollision/CollisionShapes/btCollisionShape.h>
49#include <BulletCollision/CollisionDispatch/btManifoldResult.h>
50#include <btBulletCollisionCommon.h>
51#include <console_bridge/console.h>
53
56
58{
59#define METERS
60
61const btScalar BULLET_MARGIN = btScalar(0.0);
62const btScalar BULLET_SUPPORT_FUNC_TOLERANCE = btScalar(0.01) METERS;
63const btScalar BULLET_LENGTH_TOLERANCE = btScalar(0.001) METERS;
64const btScalar BULLET_EPSILON = btScalar(1e-3);
65const btScalar BULLET_DEFAULT_CONTACT_DISTANCE = btScalar(0.05);
67
68btVector3 convertEigenToBt(const Eigen::Vector3d& v);
69
70Eigen::Vector3d convertBtToEigen(const btVector3& v);
71
72btQuaternion convertEigenToBt(const Eigen::Quaterniond& q);
73
74btMatrix3x3 convertEigenToBt(const Eigen::Matrix3d& r);
75
76Eigen::Matrix3d convertBtToEigen(const btMatrix3x3& r);
77
78btTransform convertEigenToBt(const Eigen::Isometry3d& t);
79
80Eigen::Isometry3d convertBtToEigen(const btTransform& t);
81
88class CollisionObjectWrapper : public btCollisionObject
89{
90public:
91 // LCOV_EXCL_START
92 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
93 // LCOV_EXCL_STOP
94
95 using Ptr = std::shared_ptr<CollisionObjectWrapper>;
96 using ConstPtr = std::shared_ptr<const CollisionObjectWrapper>;
97
99 CollisionObjectWrapper(std::string name,
100 const int& type_id,
103
104 short int m_collisionFilterGroup{ btBroadphaseProxy::KinematicFilter };
105 short int m_collisionFilterMask{ btBroadphaseProxy::StaticFilter | btBroadphaseProxy::KinematicFilter };
106 bool m_enabled{ true };
107
109 const std::string& getName() const;
111 const int& getTypeID() const;
113 bool sameObject(const CollisionObjectWrapper& other) const;
114
115 const CollisionShapesConst& getCollisionGeometries() const;
116
117 const tesseract_common::VectorIsometry3d& getCollisionGeometriesTransforms() const;
118
124 void getAABB(btVector3& aabb_min, btVector3& aabb_max) const;
125
130 std::shared_ptr<CollisionObjectWrapper> clone();
131
132 void manage(const std::shared_ptr<btCollisionShape>& t);
133
134 void manageReserve(std::size_t s);
135
136protected:
138 std::string m_name;
140 int m_type_id{ -1 };
141 /* @brief The shapes that define the collision object */
146 std::vector<std::shared_ptr<btCollisionShape>> m_data{};
147};
148
150using Link2Cow = std::map<std::string, COW::Ptr>;
151using Link2ConstCow = std::map<std::string, COW::ConstPtr>;
152
154struct CastHullShape : public btConvexShape
155{
156public:
157 btConvexShape* m_shape;
158 btTransform m_t01;
159
160 CastHullShape(btConvexShape* shape, const btTransform& t01);
161
162 void updateCastTransform(const btTransform& t01);
163 btVector3 localGetSupportingVertex(const btVector3& vec) const override;
164
166 void getAabb(const btTransform& t_w0, btVector3& aabbMin, btVector3& aabbMax) const override;
167
168 const char* getName() const override;
169 btVector3 localGetSupportingVertexWithoutMargin(const btVector3& v) const override;
170
171 // LCOV_EXCL_START
172 // notice that the vectors should be unit length
173 void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,
174 btVector3* supportVerticesOut,
175 int numVectors) const override;
176
177 void getAabbSlow(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const override;
178
179 void setLocalScaling(const btVector3& scaling) override;
180
181 const btVector3& getLocalScaling() const override;
182
183 void setMargin(btScalar margin) override;
184
185 btScalar getMargin() const override;
186
187 int getNumPreferredPenetrationDirections() const override;
188
189 void getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const override;
190
191 void calculateLocalInertia(btScalar, btVector3&) const override;
192 // LCOV_EXCL_STOP
193};
194
195void GetAverageSupport(const btConvexShape* shape,
196 const btVector3& localNormal,
197 btScalar& outsupport,
198 btVector3& outpt);
199
206btTransform getLinkTransformFromCOW(const btCollisionObjectWrapper* cow);
207
216bool needsCollisionCheck(const COW& cow1, const COW& cow2, const IsContactAllowedFn& acm, bool verbose = false);
217
218btScalar addDiscreteSingleResult(btManifoldPoint& cp,
219 const btCollisionObjectWrapper* colObj0Wrap,
220 const btCollisionObjectWrapper* colObj1Wrap,
221 ContactTestData& collisions);
222
233 const btCollisionObjectWrapper* cow,
234 const btVector3& pt_world,
235 const btVector3& normal_world,
236 const btTransform& link_tf_inv,
237 size_t link_index);
238
239btScalar addCastSingleResult(btManifoldPoint& cp,
240 const btCollisionObjectWrapper* colObj0Wrap,
241 int index0,
242 const btCollisionObjectWrapper* colObj1Wrap,
243 int index1,
244 ContactTestData& collisions);
245
247struct TesseractBridgedManifoldResult : public btManifoldResult
248{
249 btCollisionWorld::ContactResultCallback& m_resultCallback;
250
251 TesseractBridgedManifoldResult(const btCollisionObjectWrapper* obj0Wrap,
252 const btCollisionObjectWrapper* obj1Wrap,
253 btCollisionWorld::ContactResultCallback& resultCallback);
254
255 void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override;
256};
257
260{
264
265 BroadphaseContactResultCallback(ContactTestData& collisions, double contact_distance, bool verbose = false);
266
272
273 virtual bool needsCollision(const CollisionObjectWrapper* cow0, const CollisionObjectWrapper* cow1) const;
274
275 virtual btScalar addSingleResult(btManifoldPoint& cp,
276 const btCollisionObjectWrapper* colObj0Wrap,
277 int partId0,
278 int index0,
279 const btCollisionObjectWrapper* colObj1Wrap,
280 int partId1,
281 int index1) = 0;
282};
283
285{
286 DiscreteBroadphaseContactResultCallback(ContactTestData& collisions, double contact_distance, bool verbose = false);
287
288 btScalar addSingleResult(btManifoldPoint& cp,
289 const btCollisionObjectWrapper* colObj0Wrap,
290 int partId0,
291 int index0,
292 const btCollisionObjectWrapper* colObj1Wrap,
293 int partId1,
294 int index1) override;
295};
296
298{
299 CastBroadphaseContactResultCallback(ContactTestData& collisions, double contact_distance, bool verbose = false);
300
301 btScalar addSingleResult(btManifoldPoint& cp,
302 const btCollisionObjectWrapper* colObj0Wrap,
303 int partId0,
304 int index0,
305 const btCollisionObjectWrapper* colObj1Wrap,
306 int partId1,
307 int index1) override;
308};
309
310struct TesseractBroadphaseBridgedManifoldResult : public btManifoldResult
311{
313
314 TesseractBroadphaseBridgedManifoldResult(const btCollisionObjectWrapper* obj0Wrap,
315 const btCollisionObjectWrapper* obj1Wrap,
316 BroadphaseContactResultCallback& result_callback);
317
318 void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override;
319};
320
327class TesseractCollisionPairCallback : public btOverlapCallback
328{
329 const btDispatcherInfo& dispatch_info_;
330 btCollisionDispatcher* dispatcher_;
332
333public:
334 TesseractCollisionPairCallback(const btDispatcherInfo& dispatchInfo,
335 btCollisionDispatcher* dispatcher,
336 BroadphaseContactResultCallback& results_callback);
337
343
344 bool processOverlap(btBroadphasePair& pair) override;
345};
346
348class TesseractOverlapFilterCallback : public btOverlapFilterCallback
349{
350public:
351 TesseractOverlapFilterCallback(bool verbose = false);
352
353 bool needBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const override;
354
355private:
356 bool verbose_{ false };
357};
358
367std::shared_ptr<btCollisionShape> createShapePrimitive(const CollisionShapeConstPtr& geom,
368 CollisionObjectWrapper* cow,
369 int shape_index);
370
376void updateCollisionObjectFilters(const std::vector<std::string>& active, const COW::Ptr& cow);
377
378COW::Ptr createCollisionObject(const std::string& name,
379 const int& type_id,
380 const CollisionShapesConst& shapes,
381 const tesseract_common::VectorIsometry3d& shape_poses,
382 bool enabled = true);
383
384struct DiscreteCollisionCollector : public btCollisionWorld::ContactResultCallback
385{
390
392 COW::Ptr cow,
393 btScalar contact_distance,
394 bool verbose = false);
395
396 btScalar addSingleResult(btManifoldPoint& cp,
397 const btCollisionObjectWrapper* colObj0Wrap,
398 int partId0,
399 int index0,
400 const btCollisionObjectWrapper* colObj1Wrap,
401 int partId1,
402 int index1) override;
403
404 bool needsCollision(btBroadphaseProxy* proxy0) const override;
405};
406
407struct CastCollisionCollector : public btCollisionWorld::ContactResultCallback
408{
413
414 CastCollisionCollector(ContactTestData& collisions, COW::Ptr cow, double contact_distance, bool verbose = false);
415
416 btScalar addSingleResult(btManifoldPoint& cp,
417 const btCollisionObjectWrapper* colObj0Wrap,
418 int partId0,
419 int index0,
420 const btCollisionObjectWrapper* colObj1Wrap,
421 int partId1,
422 int index1) override;
423
424 bool needsCollision(btBroadphaseProxy* proxy0) const override;
425};
426
428
435void updateBroadphaseAABB(const COW::Ptr& cow,
436 const std::unique_ptr<btBroadphaseInterface>& broadphase,
437 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
438
446 const std::unique_ptr<btBroadphaseInterface>& broadphase,
447 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
448
456 const std::unique_ptr<btBroadphaseInterface>& broadphase,
457 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
458
466void updateCollisionObjectFilters(const std::vector<std::string>& active,
467 const COW::Ptr& cow,
468 const std::unique_ptr<btBroadphaseInterface>& broadphase,
469 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
470
480void refreshBroadphaseProxy(const COW::Ptr& cow,
481 const std::unique_ptr<btBroadphaseInterface>& broadphase,
482 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
483} // namespace tesseract_collision::tesseract_collision_bullet
484#endif // TESSERACT_COLLISION_BULLET_UTILS_H
#define METERS
Definition: bullet_utils.h:59
This is a tesseract bullet collsion object.
Definition: bullet_utils.h:89
std::shared_ptr< CollisionObjectWrapper > Ptr
Definition: bullet_utils.h:95
std::string m_name
The name of the collision object.
Definition: bullet_utils.h:138
std::shared_ptr< const CollisionObjectWrapper > ConstPtr
Definition: bullet_utils.h:96
A callback function that is called as part of the broadphase collision checking.
Definition: bullet_utils.h:328
btCollisionDispatcher * dispatcher_
Definition: bullet_utils.h:330
TesseractCollisionPairCallback & operator=(const TesseractCollisionPairCallback &)=delete
TesseractCollisionPairCallback & operator=(TesseractCollisionPairCallback &&)=delete
bool processOverlap(btBroadphasePair &pair) override
Definition: bullet_utils.cpp:1068
BroadphaseContactResultCallback & results_callback_
Definition: bullet_utils.h:331
const btDispatcherInfo & dispatch_info_
Definition: bullet_utils.h:329
TesseractCollisionPairCallback(const TesseractCollisionPairCallback &)=default
This class is used to filter broadphase.
Definition: bullet_utils.h:349
bool needBroadphaseCollision(btBroadphaseProxy *proxy0, btBroadphaseProxy *proxy1) const override
Definition: bullet_utils.cpp:1101
auto clone
Definition: clone_cache_unit.cpp:126
auto acm
Definition: collision_core_unit.cpp:33
results type_id[0]
Definition: collision_core_unit.cpp:152
This is a collection of common methods.
q[0]
Definition: kinematics_core_unit.cpp:15
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
Definition: bullet_cast_bvh_manager.h:49
btScalar addCastSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int index0, const btCollisionObjectWrapper *colObj1Wrap, int index1, ContactTestData &collisions)
Definition: bullet_utils.cpp:810
const btScalar BULLET_LENGTH_TOLERANCE
Definition: bullet_utils.h:63
const btScalar BULLET_MARGIN
Definition: bullet_utils.h:61
void GetAverageSupport(const btConvexShape *shape, const btVector3 &localNormal, btScalar &outsupport, btVector3 &outpt)
Definition: bullet_utils.cpp:614
COW::Ptr makeCastCollisionObject(const COW::Ptr &cow)
Definition: bullet_utils.cpp:1198
bool needsCollisionCheck(const COW &cow1, const COW &cow2, const IsContactAllowedFn &acm, bool verbose=false)
This is used to check if a collision check is required between the provided two collision objects.
Definition: bullet_utils.cpp:674
const btScalar BULLET_DEFAULT_CONTACT_DISTANCE
Definition: bullet_utils.h:65
Eigen::Vector3d convertBtToEigen(const btVector3 &v)
Definition: bullet_utils.cpp:65
std::map< std::string, COW::Ptr > Link2Cow
Definition: bullet_utils.h:150
void addCollisionObjectToBroadphase(const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Add the collision object to broadphase.
Definition: bullet_utils.cpp:1327
btTransform getLinkTransformFromCOW(const btCollisionObjectWrapper *cow)
This transversus the parent tree to find the base object and return its world transform This should b...
Definition: bullet_utils.cpp:658
btScalar addDiscreteSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, const btCollisionObjectWrapper *colObj1Wrap, ContactTestData &collisions)
Definition: bullet_utils.cpp:681
const btScalar BULLET_SUPPORT_FUNC_TOLERANCE
Definition: bullet_utils.h:62
COW::Ptr createCollisionObject(const std::string &name, const int &type_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)
Definition: bullet_utils.cpp:1111
const btScalar BULLET_EPSILON
Definition: bullet_utils.h:64
void refreshBroadphaseProxy(const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Refresh the broadphase data structure.
Definition: bullet_utils.cpp:1353
btVector3 convertEigenToBt(const Eigen::Vector3d &v)
Definition: bullet_utils.cpp:60
const bool BULLET_COMPOUND_USE_DYNAMIC_AABB
Definition: bullet_utils.h:66
std::map< std::string, COW::ConstPtr > Link2ConstCow
Definition: bullet_utils.h:151
void updateBroadphaseAABB(const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Update the Broadphase AABB for the input collision object.
Definition: bullet_utils.cpp:1300
void removeCollisionObjectFromBroadphase(const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Remove the collision object from broadphase.
Definition: bullet_utils.cpp:1313
std::shared_ptr< btCollisionShape > createShapePrimitive(const CollisionShapeConstPtr &geom, CollisionObjectWrapper *cow, int shape_index)
Create a bullet collision shape from tesseract collision shape.
Definition: bullet_utils.cpp:338
void updateCollisionObjectFilters(const std::vector< std::string > &active, const COW::Ptr &cow)
Update a collision objects filters.
Definition: bullet_utils.cpp:415
void calculateContinuousData(ContactResult *col, const btCollisionObjectWrapper *cow, const btVector3 &pt_world, const btVector3 &normal_world, const btTransform &link_tf_inv, size_t link_index)
Calculate the continuous contact data for casted collision shape.
Definition: bullet_utils.cpp:734
tesseract_geometry::Geometry::ConstPtr CollisionShapeConstPtr
Definition: types.h:48
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
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
Definition: types.h:62
std::set< std::string > s
Definition: plugin_loader_unit.cpp:45
This data is intended only to be used internal to the collision checkers as a container and should no...
Definition: types.h:319
The BroadphaseContactResultCallback is used to report contact points.
Definition: bullet_utils.h:260
BroadphaseContactResultCallback(const BroadphaseContactResultCallback &)=default
BroadphaseContactResultCallback & operator=(BroadphaseContactResultCallback &&)=delete
virtual bool needsCollision(const CollisionObjectWrapper *cow0, const CollisionObjectWrapper *cow1) const
Definition: bullet_utils.cpp:956
BroadphaseContactResultCallback & operator=(const BroadphaseContactResultCallback &)=delete
virtual btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1)=0
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1) override
Definition: bullet_utils.cpp:990
ContactTestData & collisions_
Definition: bullet_utils.h:409
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1) override
Definition: bullet_utils.cpp:1176
bool needsCollision(btBroadphaseProxy *proxy0) const override
Definition: bullet_utils.cpp:1191
This is a casted collision shape used for checking if an object is collision free between two transfo...
Definition: bullet_utils.h:155
const btVector3 & getLocalScaling() const override
Definition: bullet_utils.cpp:588
void getPreferredPenetrationDirection(int index, btVector3 &penetrationVector) const override
Definition: bullet_utils.cpp:600
btConvexShape * m_shape
Definition: bullet_utils.h:157
btVector3 localGetSupportingVertexWithoutMargin(const btVector3 &v) const override
Definition: bullet_utils.cpp:558
void calculateLocalInertia(btScalar, btVector3 &) const override
Definition: bullet_utils.cpp:607
btVector3 localGetSupportingVertex(const btVector3 &vec) const override
Definition: bullet_utils.cpp:540
btScalar getMargin() const override
Definition: bullet_utils.cpp:596
void setLocalScaling(const btVector3 &scaling) override
Definition: bullet_utils.cpp:581
int getNumPreferredPenetrationDirections() const override
Definition: bullet_utils.cpp:598
btTransform m_t01
Definition: bullet_utils.h:158
void getAabb(const btTransform &t_w0, btVector3 &aabbMin, btVector3 &aabbMax) const override
getAabb's default implementation is brute force, expected derived classes to implement a fast dedicat...
Definition: bullet_utils.cpp:548
void getAabbSlow(const btTransform &t, btVector3 &aabbMin, btVector3 &aabbMax) const override
Definition: bullet_utils.cpp:574
void updateCastTransform(const btTransform &t01)
Definition: bullet_utils.cpp:539
const char * getName() const override
Definition: bullet_utils.cpp:557
void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3 *vectors, btVector3 *supportVerticesOut, int numVectors) const override
Definition: bullet_utils.cpp:565
void setMargin(btScalar margin) override
Definition: bullet_utils.cpp:594
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1) override
Definition: bullet_utils.cpp:969
ContactTestData & collisions_
Definition: bullet_utils.h:386
bool needsCollision(btBroadphaseProxy *proxy0) const override
Definition: bullet_utils.cpp:1158
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1) override
Definition: bullet_utils.cpp:1144
This is copied directly out of BulletWorld.
Definition: bullet_utils.h:248
btCollisionWorld::ContactResultCallback & m_resultCallback
Definition: bullet_utils.h:249
void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth) override
Definition: bullet_utils.cpp:903
BroadphaseContactResultCallback & result_callback_
Definition: bullet_utils.h:312
void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth) override
Definition: bullet_utils.cpp:1012
Tesseracts Collision Common Types.
v
Definition: tesseract_common_unit.cpp:369
auto geom
Definition: tesseract_geometry_unit.cpp:51
auto col
Definition: tesseract_scene_graph_serialization_unit.cpp:151