43#ifndef TESSERACT_COLLISION_BULLET_UTILS_H
44#define TESSERACT_COLLISION_BULLET_UTILS_H
48#include <BulletCollision/CollisionShapes/btCollisionShape.h>
49#include <BulletCollision/CollisionDispatch/btManifoldResult.h>
50#include <btBulletCollisionCommon.h>
51#include <console_bridge/console.h>
92 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
95 using Ptr = std::shared_ptr<CollisionObjectWrapper>;
96 using ConstPtr = std::shared_ptr<const CollisionObjectWrapper>;
104 short int m_collisionFilterGroup{ btBroadphaseProxy::KinematicFilter };
105 short int m_collisionFilterMask{ btBroadphaseProxy::StaticFilter | btBroadphaseProxy::KinematicFilter };
106 bool m_enabled{
true };
109 const std::string& getName()
const;
111 const int& getTypeID()
const;
124 void getAABB(btVector3& aabb_min, btVector3& aabb_max)
const;
130 std::shared_ptr<CollisionObjectWrapper>
clone();
132 void manage(
const std::shared_ptr<btCollisionShape>& t);
134 void manageReserve(std::size_t
s);
146 std::vector<std::shared_ptr<btCollisionShape>> m_data{};
166 void getAabb(
const btTransform& t_w0, btVector3& aabbMin, btVector3& aabbMax)
const override;
168 const char*
getName()
const override;
174 btVector3* supportVerticesOut,
175 int numVectors)
const override;
177 void getAabbSlow(
const btTransform& t, btVector3& aabbMin, btVector3& aabbMax)
const override;
183 void setMargin(btScalar margin)
override;
196 const btVector3& localNormal,
197 btScalar& outsupport,
219 const btCollisionObjectWrapper* colObj0Wrap,
220 const btCollisionObjectWrapper* colObj1Wrap,
233 const btCollisionObjectWrapper* cow,
234 const btVector3& pt_world,
235 const btVector3& normal_world,
236 const btTransform& link_tf_inv,
240 const btCollisionObjectWrapper* colObj0Wrap,
242 const btCollisionObjectWrapper* colObj1Wrap,
252 const btCollisionObjectWrapper* obj1Wrap,
253 btCollisionWorld::ContactResultCallback& resultCallback);
255 void addContactPoint(
const btVector3& normalOnBInWorld,
const btVector3& pointInWorld, btScalar depth)
override;
276 const btCollisionObjectWrapper* colObj0Wrap,
279 const btCollisionObjectWrapper* colObj1Wrap,
289 const btCollisionObjectWrapper* colObj0Wrap,
292 const btCollisionObjectWrapper* colObj1Wrap,
294 int index1)
override;
302 const btCollisionObjectWrapper* colObj0Wrap,
305 const btCollisionObjectWrapper* colObj1Wrap,
307 int index1)
override;
315 const btCollisionObjectWrapper* obj1Wrap,
318 void addContactPoint(
const btVector3& normalOnBInWorld,
const btVector3& pointInWorld, btScalar depth)
override;
335 btCollisionDispatcher* dispatcher,
368 CollisionObjectWrapper* cow,
382 bool enabled =
true);
393 btScalar contact_distance,
394 bool verbose =
false);
397 const btCollisionObjectWrapper* colObj0Wrap,
400 const btCollisionObjectWrapper* colObj1Wrap,
402 int index1)
override;
417 const btCollisionObjectWrapper* colObj0Wrap,
420 const btCollisionObjectWrapper* colObj1Wrap,
422 int index1)
override;
436 const std::unique_ptr<btBroadphaseInterface>& broadphase,
437 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
446 const std::unique_ptr<btBroadphaseInterface>& broadphase,
447 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
456 const std::unique_ptr<btBroadphaseInterface>& broadphase,
457 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
468 const std::unique_ptr<btBroadphaseInterface>& broadphase,
469 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
481 const std::unique_ptr<btBroadphaseInterface>& broadphase,
482 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
#define METERS
Definition: bullet_utils.h:59
This is a tesseract bullet collsion object.
Definition: bullet_utils.h:89
CollisionObjectWrapper()=default
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(TesseractCollisionPairCallback &&)=default
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
~TesseractCollisionPairCallback() override=default
This class is used to filter broadphase.
Definition: bullet_utils.h:349
bool verbose_
Definition: bullet_utils.h:356
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
#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
Definition: bullet_utils.h:408
ContactTestData & collisions_
Definition: bullet_utils.h:409
bool verbose_
Definition: bullet_utils.h:412
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1) override
Definition: bullet_utils.cpp:1176
double contact_distance_
Definition: bullet_utils.h:411
const COW::Ptr cow_
Definition: bullet_utils.h:410
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
Definition: bullet_utils.h:385
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
const COW::Ptr cow_
Definition: bullet_utils.h:387
double contact_distance_
Definition: bullet_utils.h:388
bool verbose_
Definition: bullet_utils.h:389
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
Definition: bullet_utils.h:311
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
m name
Definition: tesseract_scene_graph_link_unit.cpp:77
auto col
Definition: tesseract_scene_graph_serialization_unit.cpp:151