moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
bullet_utils.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD-2-Clause)
3 *
4 * Copyright (c) 2017, Southwest Research Institute
5 * Copyright (c) 2013, John Schulman
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 *********************************************************************/
32
33/* Authors: John Schulman, Levi Armstrong */
34
35#pragma once
36
37#include <btBulletCollisionCommon.h>
38#include <geometric_shapes/mesh_operations.h>
39#include <rclcpp/logging.hpp>
40
46
48{
49#define METERS
50
51const btScalar BULLET_MARGIN = 0.0f;
53const btScalar BULLET_LENGTH_TOLERANCE = 0.001f METERS;
54const btScalar BULLET_EPSILON = 1e-3f; // numerical precision limit
55const btScalar BULLET_DEFAULT_CONTACT_DISTANCE = 0.00f; // All pairs closer than this distance get reported
57
59
61bool acmCheck(const std::string& body_1, const std::string& body_2,
63
65inline btVector3 convertEigenToBt(const Eigen::Vector3d& v)
66{
67 return btVector3(static_cast<btScalar>(v[0]), static_cast<btScalar>(v[1]), static_cast<btScalar>(v[2]));
68}
69
71inline Eigen::Vector3d convertBtToEigen(const btVector3& v)
72{
73 return Eigen::Vector3d(static_cast<double>(v.x()), static_cast<double>(v.y()), static_cast<double>(v.z()));
74}
75
77inline btQuaternion convertEigenToBt(const Eigen::Quaterniond& q)
78{
79 return btQuaternion(static_cast<btScalar>(q.x()), static_cast<btScalar>(q.y()), static_cast<btScalar>(q.z()),
80 static_cast<btScalar>(q.w()));
81}
82
84inline btMatrix3x3 convertEigenToBt(const Eigen::Matrix3d& r)
85{
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)));
89}
90
92inline btTransform convertEigenToBt(const Eigen::Isometry3d& t)
93{
94 const Eigen::Matrix3d& rot = t.matrix().block<3, 3>(0, 0);
95 const Eigen::Vector3d& tran = t.translation();
96
97 btMatrix3x3 mat = convertEigenToBt(rot);
98 btVector3 translation = convertEigenToBt(tran);
99
100 return btTransform(mat, translation);
101}
102
109class CollisionObjectWrapper : public btCollisionObject
110{
111public:
113
117 CollisionObjectWrapper(const std::string& name, const collision_detection::BodyType& type_id,
118 const std::vector<shapes::ShapeConstPtr>& shapes,
119 const AlignedVector<Eigen::Isometry3d>& shape_poses,
120 const std::vector<CollisionObjectType>& collision_object_types, bool active = true);
121
125 CollisionObjectWrapper(const std::string& name, const collision_detection::BodyType& type_id,
126 const std::vector<shapes::ShapeConstPtr>& shapes,
127 const AlignedVector<Eigen::Isometry3d>& shape_poses,
128 const std::vector<CollisionObjectType>& collision_object_types,
129 const std::set<std::string>& touch_links);
130
133
136
138 bool m_enabled{ true };
139
141 std::set<std::string> touch_links;
142
144 const std::string& getName() const
145 {
146 return name_;
147 }
148
151 {
152 return type_id_;
153 }
154
157 bool sameObject(const CollisionObjectWrapper& other) const
158 {
159 return name_ == other.name_ && type_id_ == other.type_id_ && shapes_.size() == other.shapes_.size() &&
160 shape_poses_.size() == other.shape_poses_.size() &&
161 std::equal(shapes_.begin(), shapes_.end(), other.shapes_.begin()) &&
162 std::equal(shape_poses_.begin(), shape_poses_.end(), other.shape_poses_.begin(),
163 [](const Eigen::Isometry3d& t1, const Eigen::Isometry3d& t2) { return t1.isApprox(t2); });
164 }
165
169 void getAABB(btVector3& aabb_min, btVector3& aabb_max) const
170 {
171 getCollisionShape()->getAabb(getWorldTransform(), aabb_min, aabb_max);
172 const btScalar& distance = getContactProcessingThreshold();
173 // note that bullet expands each AABB by 4 cm
174 btVector3 contact_threshold(distance, distance, distance);
175 aabb_min -= contact_threshold;
176 aabb_max += contact_threshold;
177 }
178
181 std::shared_ptr<CollisionObjectWrapper> clone()
182 {
183 std::shared_ptr<CollisionObjectWrapper> clone_cow(
185 clone_cow->setCollisionShape(getCollisionShape());
186 clone_cow->setWorldTransform(getWorldTransform());
187 clone_cow->m_collisionFilterGroup = m_collisionFilterGroup;
188 clone_cow->m_collisionFilterMask = m_collisionFilterMask;
189 clone_cow->m_enabled = m_enabled;
190 clone_cow->setBroadphaseHandle(nullptr);
191 clone_cow->touch_links = touch_links;
192 clone_cow->setContactProcessingThreshold(getContactProcessingThreshold());
193 return clone_cow;
194 }
195
197 template <class T>
198 void manage(T* t)
199 {
200 data_.push_back(std::shared_ptr<T>(t));
201 }
202
204 template <class T>
205 void manage(std::shared_ptr<T> t)
206 {
207 data_.push_back(t);
208 }
209
210protected:
212 CollisionObjectWrapper(const std::string& name, const collision_detection::BodyType& type_id,
213 const std::vector<shapes::ShapeConstPtr>& shapes,
214 const AlignedVector<Eigen::Isometry3d>& shape_poses,
215 const std::vector<CollisionObjectType>& collision_object_types,
216 const std::vector<std::shared_ptr<void>>& data);
217
219 std::string name_;
220
222
224 std::vector<shapes::ShapeConstPtr> shapes_;
225
228
230 std::vector<CollisionObjectType> collision_object_types_;
231
233 std::vector<std::shared_ptr<void>> data_;
234};
235
240struct CastHullShape : public btConvexShape
241{
242public:
244 btConvexShape* m_shape;
245
247 btTransform shape_transform;
248
249 CastHullShape(btConvexShape* shape, const btTransform& t01) : m_shape(shape), shape_transform(t01)
250 {
251 m_shapeType = CUSTOM_CONVEX_SHAPE_TYPE;
252 }
253
254 void updateCastTransform(const btTransform& cast_transform)
255 {
256 shape_transform = cast_transform;
257 }
258
260 btVector3 localGetSupportingVertex(const btVector3& vec) const override
261 {
262 btVector3 support_vector_0 = m_shape->localGetSupportingVertex(vec);
263 btVector3 support_vector_1 = shape_transform * m_shape->localGetSupportingVertex(vec * shape_transform.getBasis());
264 return (vec.dot(support_vector_0) > vec.dot(support_vector_1)) ? support_vector_0 : support_vector_1;
265 }
266
267 void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* /*vectors*/,
268 btVector3* /*supportVerticesOut*/,
269 int /*numVectors*/) const override
270 {
271 throw std::runtime_error("not implemented");
272 }
273
277 void getAabb(const btTransform& transform_world, btVector3& aabbMin, btVector3& aabbMax) const override
278 {
279 m_shape->getAabb(transform_world, aabbMin, aabbMax);
280 btVector3 min1, max1;
281 m_shape->getAabb(transform_world * shape_transform, min1, max1);
282 aabbMin.setMin(min1);
283 aabbMax.setMax(max1);
284 }
285
286 void getAabbSlow(const btTransform& /*t*/, btVector3& /*aabbMin*/, btVector3& /*aabbMax*/) const override
287 {
288 throw std::runtime_error("shouldn't happen");
289 }
290
291 void setLocalScaling(const btVector3& /*scaling*/) override
292 {
293 }
294
295 const btVector3& getLocalScaling() const override
296 {
297 static btVector3 out(1, 1, 1);
298 return out;
299 }
300
301 void setMargin(btScalar /*margin*/) override
302 {
303 }
304
305 btScalar getMargin() const override
306 {
307 return 0;
308 }
309
311 {
312 return 0;
313 }
314
315 void getPreferredPenetrationDirection(int /*index*/, btVector3& /*penetrationVector*/) const override
316 {
317 throw std::runtime_error("not implemented");
318 }
319
320 void calculateLocalInertia(btScalar /*mass*/, btVector3& /*inertia*/) const override
321 {
322 throw std::runtime_error("not implemented");
323 }
324
325 const char* getName() const override
326 {
327 return "CastHull";
328 }
329
330 btVector3 localGetSupportingVertexWithoutMargin(const btVector3& v) const override
331 {
332 return localGetSupportingVertex(v);
333 }
334};
335
344inline void getAverageSupport(const btConvexShape* shape, const btVector3& localNormal, float& outsupport,
345 btVector3& outpt)
346{
347 btVector3 pt_sum(0, 0, 0);
348 float pt_count = 0;
349 float max_support = -1000;
350
351 const btPolyhedralConvexShape* pshape = dynamic_cast<const btPolyhedralConvexShape*>(shape);
352 if (pshape)
353 {
354 int n_pts = pshape->getNumVertices();
355
356 for (int i = 0; i < n_pts; ++i)
357 {
358 btVector3 pt;
359 pshape->getVertex(i, pt);
360
361 float sup = pt.dot(localNormal);
362 if (sup > max_support + BULLET_EPSILON)
363 {
364 pt_count = 1;
365 pt_sum = pt;
366 max_support = sup;
367 }
368 else if (sup < max_support - BULLET_EPSILON) {}
369 else
370 {
371 pt_count += 1;
372 pt_sum += pt;
373 }
374 }
375 outsupport = max_support;
376 outpt = pt_sum / pt_count;
377 }
378 else
379 {
380 outpt = shape->localGetSupportingVertexWithoutMargin(localNormal);
381 outsupport = localNormal.dot(outpt);
382 }
383}
384
386inline btScalar addDiscreteSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,
387 const btCollisionObjectWrapper* colObj1Wrap, ContactTestData& collisions)
388{
389 assert(dynamic_cast<const CollisionObjectWrapper*>(colObj0Wrap->getCollisionObject()) != nullptr);
390 assert(dynamic_cast<const CollisionObjectWrapper*>(colObj1Wrap->getCollisionObject()) != nullptr);
391 const CollisionObjectWrapper* cd0 = static_cast<const CollisionObjectWrapper*>(colObj0Wrap->getCollisionObject());
392 const CollisionObjectWrapper* cd1 = static_cast<const CollisionObjectWrapper*>(colObj1Wrap->getCollisionObject());
393
394 std::pair<std::string, std::string> pc = getObjectPairKey(cd0->getName(), cd1->getName());
395
396 const auto& it = collisions.res.contacts.find(pc);
397 bool found = (it != collisions.res.contacts.end());
398
400 contact.body_name_1 = cd0->getName();
401 contact.body_name_2 = cd1->getName();
402 contact.depth = static_cast<double>(cp.m_distance1);
403 contact.normal = convertBtToEigen(-1 * cp.m_normalWorldOnB);
404 contact.pos = convertBtToEigen(cp.m_positionWorldOnA);
405 contact.nearest_points[0] = contact.pos;
406 contact.nearest_points[1] = convertBtToEigen(cp.m_positionWorldOnB);
407
408 contact.body_type_1 = cd0->getTypeID();
409 contact.body_type_2 = cd1->getTypeID();
410
411 if (!processResult(collisions, contact, pc, found))
412 {
413 return 0;
414 }
415
416 return 1;
417}
418
419inline btScalar addCastSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int /*index0*/,
420 const btCollisionObjectWrapper* colObj1Wrap, int /*index1*/,
421 ContactTestData& collisions)
422{
423 assert(dynamic_cast<const CollisionObjectWrapper*>(colObj0Wrap->getCollisionObject()) != nullptr);
424 assert(dynamic_cast<const CollisionObjectWrapper*>(colObj1Wrap->getCollisionObject()) != nullptr);
425
426 const CollisionObjectWrapper* cd0 = static_cast<const CollisionObjectWrapper*>(colObj0Wrap->getCollisionObject());
427 const CollisionObjectWrapper* cd1 = static_cast<const CollisionObjectWrapper*>(colObj1Wrap->getCollisionObject());
428
429 std::pair<std::string, std::string> pc = getObjectPairKey(cd0->getName(), cd1->getName());
430
431 const auto& it = collisions.res.contacts.find(pc);
432 bool found = (it != collisions.res.contacts.end());
433
435 contact.body_name_1 = cd0->getName();
436 contact.body_name_2 = cd1->getName();
437 contact.depth = static_cast<double>(cp.m_distance1);
438 contact.normal = convertBtToEigen(-1 * cp.m_normalWorldOnB);
439 contact.pos = convertBtToEigen(cp.m_positionWorldOnA);
440
441 contact.body_type_1 = cd0->getTypeID();
442 contact.body_type_2 = cd1->getTypeID();
443
444 collision_detection::Contact* col = processResult(collisions, contact, pc, found);
445
446 if (!col)
447 {
448 return 0;
449 }
450
451 assert(!((cd0->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter) &&
452 (cd1->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter)));
453
454 bool cast_shape_is_first = cd0->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter;
455
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);
458
459 // we want the contact information of the non-casted object come first, therefore swap values
460 if (cast_shape_is_first)
461 {
462 std::swap(col->nearest_points[0], col->nearest_points[1]);
463 contact.pos = convertBtToEigen(cp.m_positionWorldOnB);
464 std::swap(col->body_name_1, col->body_name_2);
465 std::swap(col->body_type_1, col->body_type_2);
466 col->normal *= -1;
467 }
468
469 btTransform tf_world0, tf_world1;
470 const CastHullShape* shape = static_cast<const CastHullShape*>(first_col_obj_wrap->getCollisionShape());
471
472 tf_world0 = first_col_obj_wrap->getWorldTransform();
473 tf_world1 = first_col_obj_wrap->getWorldTransform() * shape->shape_transform;
474
475 // transform normals into pose local coordinate systems
476 btVector3 normal_local0 = normal_world_from_cast * tf_world0.getBasis();
477 btVector3 normal_local1 = normal_world_from_cast * tf_world1.getBasis();
478
479 btVector3 pt_local0;
480 float localsup0;
481 getAverageSupport(shape->m_shape, normal_local0, localsup0, pt_local0);
482 btVector3 pt_world0 = tf_world0 * pt_local0;
483 btVector3 pt_local1;
484 float localsup1;
485 getAverageSupport(shape->m_shape, normal_local1, localsup1, pt_local1);
486 btVector3 pt_world1 = tf_world1 * pt_local1;
487
488 float sup0 = normal_world_from_cast.dot(pt_world0);
489 float sup1 = normal_world_from_cast.dot(pt_world1);
490
491 // TODO: this section is potentially problematic. think hard about the math
492 if (sup0 - sup1 > BULLET_SUPPORT_FUNC_TOLERANCE)
493 {
494 col->percent_interpolation = 0;
495 }
496 else if (sup1 - sup0 > BULLET_SUPPORT_FUNC_TOLERANCE)
497 {
498 col->percent_interpolation = 1;
499 }
500 else
501 {
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();
505
506 if (l0c + l1c < BULLET_LENGTH_TOLERANCE)
507 {
508 col->percent_interpolation = .5;
509 }
510 else
511 {
512 col->percent_interpolation = static_cast<double>(l0c / (l0c + l1c));
513 }
514 }
515
516 return 1;
517}
518
521{
522 return cow0->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter &&
523 cow1->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter;
524}
525
531{
535
537 bool self_;
538
540 bool cast_{ false };
541
542 BroadphaseContactResultCallback(ContactTestData& collisions, double contact_distance,
543 const collision_detection::AllowedCollisionMatrix* acm, bool self, bool cast = false)
544 : collisions_(collisions), contact_distance_(contact_distance), acm_(acm), self_(self), cast_(cast)
545 {
546 }
547
549
552 // TODO: Add check for two objects attached to the same link
554 {
555 if (cast_)
556 {
557 return !collisions_.done && !isOnlyKinematic(cow0, cow1) && !acmCheck(cow0->getName(), cow1->getName(), acm_);
558 }
559 else
560 {
561 return !collisions_.done && (self_ ? isOnlyKinematic(cow0, cow1) : !isOnlyKinematic(cow0, cow1)) &&
562 !acmCheck(cow0->getName(), cow1->getName(), acm_);
563 }
564 }
565
567 btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0,
568 const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1);
569};
570
571struct TesseractBroadphaseBridgedManifoldResult : public btManifoldResult
572{
574
575 TesseractBroadphaseBridgedManifoldResult(const btCollisionObjectWrapper* obj0Wrap,
576 const btCollisionObjectWrapper* obj1Wrap,
577 BroadphaseContactResultCallback& result_callback)
578 : btManifoldResult(obj0Wrap, obj1Wrap), result_callback_(result_callback)
579 {
580 }
581
582 void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override
583 {
585 depth > static_cast<btScalar>(result_callback_.contact_distance_))
586 {
587 return;
588 }
589
590 bool is_swapped = m_manifoldPtr->getBody0() != m_body0Wrap->getCollisionObject();
591 btVector3 point_a = pointInWorld + normalOnBInWorld * depth;
592 btVector3 local_a;
593 btVector3 local_b;
594 if (is_swapped)
595 {
596 local_a = m_body1Wrap->getCollisionObject()->getWorldTransform().invXform(point_a);
597 local_b = m_body0Wrap->getCollisionObject()->getWorldTransform().invXform(pointInWorld);
598 }
599 else
600 {
601 local_a = m_body0Wrap->getCollisionObject()->getWorldTransform().invXform(point_a);
602 local_b = m_body1Wrap->getCollisionObject()->getWorldTransform().invXform(pointInWorld);
603 }
604
605 btManifoldPoint new_pt(local_a, local_b, normalOnBInWorld, depth);
606 new_pt.m_positionWorldOnA = point_a;
607 new_pt.m_positionWorldOnB = pointInWorld;
608
609 // BP mod, store contact triangles.
610 if (is_swapped)
611 {
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;
616 }
617 else
618 {
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;
623 }
624
625 // experimental feature info, for per-triangle material etc.
626 const btCollisionObjectWrapper* obj0_wrap = is_swapped ? m_body1Wrap : m_body0Wrap;
627 const btCollisionObjectWrapper* obj1_wrap = is_swapped ? m_body0Wrap : m_body1Wrap;
628 result_callback_.addSingleResult(new_pt, obj0_wrap, new_pt.m_partId0, new_pt.m_index0, obj1_wrap, new_pt.m_partId1,
629 new_pt.m_index1);
630 }
631};
632
637class TesseractCollisionPairCallback : public btOverlapCallback
638{
639 const btDispatcherInfo& dispatch_info_;
640 btCollisionDispatcher* dispatcher_;
641
643 BroadphaseContactResultCallback& results_callback_;
644
645public:
646 TesseractCollisionPairCallback(const btDispatcherInfo& dispatchInfo, btCollisionDispatcher* dispatcher,
647 BroadphaseContactResultCallback& results_callback)
648 : dispatch_info_(dispatchInfo), dispatcher_(dispatcher), results_callback_(results_callback)
649 {
650 }
651
653
654 bool processOverlap(btBroadphasePair& pair) override;
655};
656
658btCollisionShape* createShapePrimitive(const shapes::ShapeConstPtr& geom,
659 const CollisionObjectType& collision_object_type, CollisionObjectWrapper* cow);
660
669void updateCollisionObjectFilters(const std::vector<std::string>& active, CollisionObjectWrapper& cow);
670
671CollisionObjectWrapperPtr makeCastCollisionObject(const CollisionObjectWrapperPtr& cow);
672
677inline void updateBroadphaseAABB(const CollisionObjectWrapperPtr& cow,
678 const std::unique_ptr<btBroadphaseInterface>& broadphase,
679 const std::unique_ptr<btCollisionDispatcher>& dispatcher)
680{
681 btVector3 aabb_min, aabb_max;
682 cow->getAABB(aabb_min, aabb_max);
683
684 assert(cow->getBroadphaseHandle() != nullptr);
685 broadphase->setAabb(cow->getBroadphaseHandle(), aabb_min, aabb_max, dispatcher.get());
686}
687
692inline void removeCollisionObjectFromBroadphase(const CollisionObjectWrapperPtr& cow,
693 const std::unique_ptr<btBroadphaseInterface>& broadphase,
694 const std::unique_ptr<btCollisionDispatcher>& dispatcher)
695{
696 btBroadphaseProxy* bp = cow->getBroadphaseHandle();
697 if (bp)
698 {
699 // only clear the cached algorithms
700 broadphase->getOverlappingPairCache()->cleanProxyFromPairs(bp, dispatcher.get());
701 broadphase->destroyProxy(bp, dispatcher.get());
702 cow->setBroadphaseHandle(nullptr);
703 }
704}
705
710void addCollisionObjectToBroadphase(const CollisionObjectWrapperPtr& cow,
711 const std::unique_ptr<btBroadphaseInterface>& broadphase,
712 const std::unique_ptr<btCollisionDispatcher>& dispatcher);
713
714struct BroadphaseFilterCallback : public btOverlapFilterCallback
715{
716 bool needBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const override;
717};
718
719} // namespace collision_detection_bullet
#define METERS
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...
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.
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)
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
Definition basic_types.h:37
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.
Definition world.h:49
Definition of a contact point.
std::string body_name_2
The id of the second body involved in the contact.
double percent_interpolation
The distance percentage between casted poses until collision.
Eigen::Vector3d nearest_points[2]
The two nearest points connecting the two bodies.
std::string body_name_1
The id of the first body involved in the contact.
BodyType body_type_1
The type of the first body involved in the contact.
BodyType body_type_2
The type of the second body involved in the contact.
Eigen::Vector3d normal
normal unit vector at contact
double depth
depth (penetration between bodies)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d pos
contact position
Callback structure for both discrete and continuous broadphase collision pair.
btScalar addSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper *colObj1Wrap, int partId1, int index1)
This callback is used after btManifoldResult processed a collision result.
bool needsCollision(const CollisionObjectWrapper *cow0, const CollisionObjectWrapper *cow1) const
This callback is used for each overlapping pair in a pair cache of the broadphase interface to check ...
const collision_detection::AllowedCollisionMatrix * acm_
bool cast_
Indicates if the callback is used for casted collisions.
bool self_
Indicates if the callback is used for only self-collision checking.
BroadphaseContactResultCallback(ContactTestData &collisions, double contact_distance, const collision_detection::AllowedCollisionMatrix *acm, bool self, bool cast=false)
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
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)
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
Bundles the data for a collision query.
Definition basic_types.h:59
bool done
Indicates if search is finished.
Definition basic_types.h:77
collision_detection::CollisionResult & res
Definition basic_types.h:73
bool pair_done
Indicates if search between a single pair is finished.
Definition basic_types.h:80
TesseractBroadphaseBridgedManifoldResult(const btCollisionObjectWrapper *obj0Wrap, const btCollisionObjectWrapper *obj1Wrap, BroadphaseContactResultCallback &result_callback)
void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth) override