37#include <btBulletCollisionCommon.h>
38#include <geometric_shapes/mesh_operations.h>
39#include <rclcpp/logging.hpp>
61bool acmCheck(
const std::string& body_1,
const std::string& body_2,
67 return btVector3(
static_cast<btScalar
>(v[0]),
static_cast<btScalar
>(v[1]),
static_cast<btScalar
>(v[2]));
73 return Eigen::Vector3d(
static_cast<double>(v.x()),
static_cast<double>(v.y()),
static_cast<double>(v.z()));
79 return btQuaternion(
static_cast<btScalar
>(q.x()),
static_cast<btScalar
>(q.y()),
static_cast<btScalar
>(q.z()),
80 static_cast<btScalar
>(q.w()));
86 return btMatrix3x3(
static_cast<btScalar
>(r(0, 0)),
static_cast<btScalar
>(r(0, 1)),
static_cast<btScalar
>(r(0, 2)),
87 static_cast<btScalar
>(r(1, 0)),
static_cast<btScalar
>(r(1, 1)),
static_cast<btScalar
>(r(1, 2)),
88 static_cast<btScalar
>(r(2, 0)),
static_cast<btScalar
>(r(2, 1)),
static_cast<btScalar
>(r(2, 2)));
94 const Eigen::Matrix3d& rot = t.matrix().block<3, 3>(0, 0);
95 const Eigen::Vector3d& tran = t.translation();
100 return btTransform(mat, translation);
118 const std::vector<shapes::ShapeConstPtr>&
shapes,
120 const std::vector<CollisionObjectType>& collision_object_types,
bool active =
true);
126 const std::vector<shapes::ShapeConstPtr>&
shapes,
128 const std::vector<CollisionObjectType>& collision_object_types,
163 [](
const Eigen::Isometry3d& t1,
const Eigen::Isometry3d& t2) { return t1.isApprox(t2); });
169 void getAABB(btVector3& aabb_min, btVector3& aabb_max)
const
171 getCollisionShape()->getAabb(getWorldTransform(), aabb_min, aabb_max);
172 const btScalar& distance = getContactProcessingThreshold();
174 btVector3 contact_threshold(distance, distance, distance);
175 aabb_min -= contact_threshold;
176 aabb_max += contact_threshold;
181 std::shared_ptr<CollisionObjectWrapper>
clone()
183 std::shared_ptr<CollisionObjectWrapper> clone_cow(
185 clone_cow->setCollisionShape(getCollisionShape());
186 clone_cow->setWorldTransform(getWorldTransform());
190 clone_cow->setBroadphaseHandle(
nullptr);
192 clone_cow->setContactProcessingThreshold(getContactProcessingThreshold());
200 data_.push_back(std::shared_ptr<T>(t));
213 const std::vector<shapes::ShapeConstPtr>&
shapes,
215 const std::vector<CollisionObjectType>& collision_object_types,
216 const std::vector<std::shared_ptr<void>>& data);
233 std::vector<std::shared_ptr<void>>
data_;
251 m_shapeType = CUSTOM_CONVEX_SHAPE_TYPE;
262 btVector3 support_vector_0 =
m_shape->localGetSupportingVertex(vec);
264 return (vec.dot(support_vector_0) > vec.dot(support_vector_1)) ? support_vector_0 : support_vector_1;
271 throw std::runtime_error(
"not implemented");
277 void getAabb(
const btTransform& transform_world, btVector3& aabbMin, btVector3& aabbMax)
const override
279 m_shape->getAabb(transform_world, aabbMin, aabbMax);
280 btVector3 min1, max1;
282 aabbMin.setMin(min1);
283 aabbMax.setMax(max1);
286 void getAabbSlow(
const btTransform& , btVector3& , btVector3& )
const override
288 throw std::runtime_error(
"shouldn't happen");
297 static btVector3 out(1, 1, 1);
317 throw std::runtime_error(
"not implemented");
322 throw std::runtime_error(
"not implemented");
344inline void getAverageSupport(
const btConvexShape* shape,
const btVector3& localNormal,
float& outsupport,
347 btVector3 pt_sum(0, 0, 0);
349 float max_support = -1000;
351 const btPolyhedralConvexShape* pshape =
dynamic_cast<const btPolyhedralConvexShape*
>(shape);
354 int n_pts = pshape->getNumVertices();
356 for (
int i = 0; i < n_pts; ++i)
359 pshape->getVertex(i, pt);
361 float sup = pt.dot(localNormal);
375 outsupport = max_support;
376 outpt = pt_sum / pt_count;
380 outpt = shape->localGetSupportingVertexWithoutMargin(localNormal);
381 outsupport = localNormal.dot(outpt);
387 const btCollisionObjectWrapper* colObj1Wrap,
ContactTestData& collisions)
397 bool found = (it != collisions.
res.
contacts.end());
402 contact.
depth =
static_cast<double>(cp.m_distance1);
419inline btScalar
addCastSingleResult(btManifoldPoint& cp,
const btCollisionObjectWrapper* colObj0Wrap,
int ,
420 const btCollisionObjectWrapper* colObj1Wrap,
int ,
432 bool found = (it != collisions.
res.
contacts.end());
437 contact.
depth =
static_cast<double>(cp.m_distance1);
456 btVector3 normal_world_from_cast = (cast_shape_is_first ? -1 : 1) * cp.m_normalWorldOnB;
457 const btCollisionObjectWrapper* first_col_obj_wrap = (cast_shape_is_first ? colObj0Wrap : colObj1Wrap);
460 if (cast_shape_is_first)
469 btTransform tf_world0, tf_world1;
472 tf_world0 = first_col_obj_wrap->getWorldTransform();
473 tf_world1 = first_col_obj_wrap->getWorldTransform() * shape->
shape_transform;
476 btVector3 normal_local0 = normal_world_from_cast * tf_world0.getBasis();
477 btVector3 normal_local1 = normal_world_from_cast * tf_world1.getBasis();
482 btVector3 pt_world0 = tf_world0 * pt_local0;
486 btVector3 pt_world1 = tf_world1 * pt_local1;
488 float sup0 = normal_world_from_cast.dot(pt_world0);
489 float sup1 = normal_world_from_cast.dot(pt_world1);
502 const btVector3& pt_on_cast = cast_shape_is_first ? cp.m_positionWorldOnA : cp.m_positionWorldOnB;
503 float l0c = (pt_on_cast - pt_world0).length();
504 float l1c = (pt_on_cast - pt_world1).length();
567 btScalar
addSingleResult(btManifoldPoint& cp,
const btCollisionObjectWrapper* colObj0Wrap,
int partId0,
int index0,
568 const btCollisionObjectWrapper* colObj1Wrap,
int partId1,
int index1);
576 const btCollisionObjectWrapper* obj1Wrap,
582 void addContactPoint(
const btVector3& normalOnBInWorld,
const btVector3& pointInWorld, btScalar depth)
override
590 bool is_swapped = m_manifoldPtr->getBody0() != m_body0Wrap->getCollisionObject();
591 btVector3 point_a = pointInWorld + normalOnBInWorld * depth;
596 local_a = m_body1Wrap->getCollisionObject()->getWorldTransform().invXform(point_a);
597 local_b = m_body0Wrap->getCollisionObject()->getWorldTransform().invXform(pointInWorld);
601 local_a = m_body0Wrap->getCollisionObject()->getWorldTransform().invXform(point_a);
602 local_b = m_body1Wrap->getCollisionObject()->getWorldTransform().invXform(pointInWorld);
605 btManifoldPoint new_pt(local_a, local_b, normalOnBInWorld, depth);
606 new_pt.m_positionWorldOnA = point_a;
607 new_pt.m_positionWorldOnB = pointInWorld;
612 new_pt.m_partId0 = m_partId1;
613 new_pt.m_partId1 = m_partId0;
614 new_pt.m_index0 = m_index1;
615 new_pt.m_index1 = m_index0;
619 new_pt.m_partId0 = m_partId0;
620 new_pt.m_partId1 = m_partId1;
621 new_pt.m_index0 = m_index0;
622 new_pt.m_index1 = m_index1;
626 const btCollisionObjectWrapper* obj0_wrap = is_swapped ? m_body1Wrap : m_body0Wrap;
627 const btCollisionObjectWrapper* obj1_wrap = is_swapped ? m_body0Wrap : m_body1Wrap;
639 const btDispatcherInfo& dispatch_info_;
640 btCollisionDispatcher* dispatcher_;
648 : dispatch_info_(dispatchInfo), dispatcher_(dispatcher), results_callback_(results_callback)
678 const std::unique_ptr<btBroadphaseInterface>& broadphase,
679 const std::unique_ptr<btCollisionDispatcher>& dispatcher)
681 btVector3 aabb_min, aabb_max;
682 cow->getAABB(aabb_min, aabb_max);
684 assert(cow->getBroadphaseHandle() !=
nullptr);
685 broadphase->setAabb(cow->getBroadphaseHandle(), aabb_min, aabb_max, dispatcher.get());
693 const std::unique_ptr<btBroadphaseInterface>& broadphase,
694 const std::unique_ptr<btCollisionDispatcher>& dispatcher)
696 btBroadphaseProxy* bp = cow->getBroadphaseHandle();
700 broadphase->getOverlappingPairCache()->cleanProxyFromPairs(bp, dispatcher.get());
701 broadphase->destroyProxy(bp, dispatcher.get());
702 cow->setBroadphaseHandle(
nullptr);
711 const std::unique_ptr<btBroadphaseInterface>& broadphase,
712 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Tesseract bullet collision object.
void manage(std::shared_ptr< T > t)
Manage memory of a shared pointer shape.
short int m_collisionFilterGroup
Bitfield specifies to which group the object belongs.
AlignedVector< Eigen::Isometry3d > shape_poses_
The poses of the shapes, must be same length as m_shapes.
std::vector< shapes::ShapeConstPtr > shapes_
The shapes that define the collision object.
bool m_enabled
Indicates if the collision object is used for a collision check.
void getAABB(btVector3 &aabb_min, btVector3 &aabb_max) const
Get the collision objects axis aligned bounding box.
std::string name_
The name of the object, must be unique.
const collision_detection::BodyType & getTypeID() const
Get a user defined type.
std::set< std::string > touch_links
The robot links the collision objects is allowed to touch.
collision_detection::BodyType type_id_
void manage(T *t)
Manage memory of a raw pointer shape.
std::shared_ptr< CollisionObjectWrapper > clone()
Clones the collision objects but not the collision shape which is const.
const std::string & getName() const
Get the collision object name.
bool sameObject(const CollisionObjectWrapper &other) const
Check if two CollisionObjectWrapper objects point to the same source object.
std::vector< std::shared_ptr< void > > data_
Manages the collision shape pointer so they get destroyed.
short int m_collisionFilterMask
Bitfield specifies against which other groups the object is collision checked.
std::vector< CollisionObjectType > collision_object_types_
The shape collision object type to be used.
A callback function that is called as part of the broadphase collision checking.
TesseractCollisionPairCallback(const btDispatcherInfo &dispatchInfo, btCollisionDispatcher *dispatcher, BroadphaseContactResultCallback &results_callback)
~TesseractCollisionPairCallback() override=default
bool processOverlap(btBroadphasePair &pair) override
Type
The types of bodies that are considered for collision.
btCollisionShape * createShapePrimitive(const shapes::ShapeConstPtr &geom, const CollisionObjectType &collision_object_type, CollisionObjectWrapper *cow)
Casts a geometric shape into a btCollisionShape.
btVector3 convertEigenToBt(const Eigen::Vector3d &v)
Converts eigen vector to bullet vector.
const btScalar BULLET_MARGIN
CollisionObjectWrapperPtr makeCastCollisionObject(const CollisionObjectWrapperPtr &cow)
collision_detection::Contact * processResult(ContactTestData &cdata, collision_detection::Contact &contact, const std::pair< std::string, std::string > &key, bool found)
Stores a single contact result in the requested way.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
void updateCollisionObjectFilters(const std::vector< std::string > &active, CollisionObjectWrapper &cow)
Update a collision objects filters.
bool acmCheck(const std::string &body_1, const std::string &body_2, const collision_detection::AllowedCollisionMatrix *acm)
Allowed = true.
std::pair< std::string, std::string > getObjectPairKey(const std::string &obj1, const std::string &obj2)
Get a key for two object to search the collision matrix.
const btScalar BULLET_EPSILON
const bool BULLET_COMPOUND_USE_DYNAMIC_AABB
const btScalar BULLET_LENGTH_TOLERANCE
btScalar addCastSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int, const btCollisionObjectWrapper *colObj1Wrap, int, ContactTestData &collisions)
void updateBroadphaseAABB(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Update the Broadphase AABB for the input collision object.
Eigen::Vector3d convertBtToEigen(const btVector3 &v)
Converts bullet vector to eigen vector.
void removeCollisionObjectFromBroadphase(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Remove the collision object from broadphase.
void addCollisionObjectToBroadphase(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Add the collision object to broadphase.
bool isOnlyKinematic(const CollisionObjectWrapper *cow0, const CollisionObjectWrapper *cow1)
Checks if the collision pair is kinematic vs kinematic objects.
const btScalar BULLET_SUPPORT_FUNC_TOLERANCE
const btScalar BULLET_DEFAULT_CONTACT_DISTANCE
btScalar addDiscreteSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, const btCollisionObjectWrapper *colObj1Wrap, ContactTestData &collisions)
Converts a bullet contact result to MoveIt format and adds it to the result data structure.
void getAverageSupport(const btConvexShape *shape, const btVector3 &localNormal, float &outsupport, btVector3 &outpt)
Computes the local supporting vertex of a convex shape.
bool needBroadphaseCollision(btBroadphaseProxy *proxy0, btBroadphaseProxy *proxy1) const override
Casted collision shape used for checking if an object is collision free between two discrete poses.
int getNumPreferredPenetrationDirections() const override
btScalar getMargin() const override
void getAabbSlow(const btTransform &, btVector3 &, btVector3 &) const override
btVector3 localGetSupportingVertex(const btVector3 &vec) const override
From both shape poses computes the support vertex and returns the larger one.
void updateCastTransform(const btTransform &cast_transform)
void setMargin(btScalar) override
const char * getName() const override
const btVector3 & getLocalScaling() const override
void calculateLocalInertia(btScalar, btVector3 &) const override
void getPreferredPenetrationDirection(int, btVector3 &) const override
void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3 *, btVector3 *, int) const override
CastHullShape(btConvexShape *shape, const btTransform &t01)
btTransform shape_transform
Transformation from the first pose to the second pose.
void getAabb(const btTransform &transform_world, btVector3 &aabbMin, btVector3 &aabbMax) const override
Shape specific fast recalculation of the AABB at a certain pose.
btVector3 localGetSupportingVertexWithoutMargin(const btVector3 &v) const override
btConvexShape * m_shape
The casted shape.
void setLocalScaling(const btVector3 &) override
TesseractBroadphaseBridgedManifoldResult(const btCollisionObjectWrapper *obj0Wrap, const btCollisionObjectWrapper *obj1Wrap, BroadphaseContactResultCallback &result_callback)
BroadphaseContactResultCallback & result_callback_
void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth) override