moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
bullet_utils.cpp
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
36
37#include <BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h>
38#include <BulletCollision/CollisionShapes/btShapeHull.h>
39#include <BulletCollision/Gimpact/btGImpactShape.h>
40#include <geometric_shapes/shapes.h>
41#include <memory>
42#include <octomap/octomap.h>
43#include <rclcpp/logger.hpp>
44#include <rclcpp/logging.hpp>
46
48{
49bool acmCheck(const std::string& body_1, const std::string& body_2,
51{
53
54 if (acm != nullptr)
55 {
56 if (acm->getAllowedCollision(body_1, body_2, allowed_type))
57 {
59 {
60 RCLCPP_DEBUG_STREAM(getLogger(),
61 "Not allowed entry in ACM found, collision check between " << body_1 << " and " << body_2);
62 return false;
63 }
64 else
65 {
66 RCLCPP_DEBUG_STREAM(getLogger(),
67 "Entry in ACM found, skipping collision check as allowed " << body_1 << " and " << body_2);
68 return true;
69 }
70 }
71 else
72 {
73 RCLCPP_DEBUG_STREAM(getLogger(), "No entry in ACM found, collision check between " << body_1 << " and " << body_2);
74 return false;
75 }
76 }
77 else
78 {
79 RCLCPP_DEBUG_STREAM(getLogger(), "No ACM, collision check between " << body_1 << " and " << body_2);
80 return false;
81 }
82}
83
84btCollisionShape* createShapePrimitive(const shapes::Box* geom, const CollisionObjectType& collision_object_type)
85{
86 static_cast<void>(collision_object_type);
87 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE);
88 const double* size = geom->size;
89 btScalar a = static_cast<btScalar>(size[0] / 2);
90 btScalar b = static_cast<btScalar>(size[1] / 2);
91 btScalar c = static_cast<btScalar>(size[2] / 2);
92
93 return (new btBoxShape(btVector3(a, b, c)));
94}
95
96btCollisionShape* createShapePrimitive(const shapes::Sphere* geom, const CollisionObjectType& collision_object_type)
97{
98 static_cast<void>(collision_object_type);
99 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE);
100 return (new btSphereShape(static_cast<btScalar>(geom->radius)));
101}
102
103btCollisionShape* createShapePrimitive(const shapes::Cylinder* geom, const CollisionObjectType& collision_object_type)
104{
105 static_cast<void>(collision_object_type);
106 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE);
107 btScalar r = static_cast<btScalar>(geom->radius);
108 btScalar l = static_cast<btScalar>(geom->length / 2);
109 return (new btCylinderShapeZ(btVector3(r, r, l)));
110}
111
112btCollisionShape* createShapePrimitive(const shapes::Cone* geom, const CollisionObjectType& collision_object_type)
113{
114 static_cast<void>(collision_object_type);
115 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE);
116 btScalar r = static_cast<btScalar>(geom->radius);
117 btScalar l = static_cast<btScalar>(geom->length);
118 return (new btConeShapeZ(r, l));
119}
120
121btCollisionShape* createShapePrimitive(const shapes::Mesh* geom, const CollisionObjectType& collision_object_type,
123{
124 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE ||
125 collision_object_type == CollisionObjectType::CONVEX_HULL ||
126 collision_object_type == CollisionObjectType::SDF);
127
128 if (geom->vertex_count > 0 && geom->triangle_count > 0)
129 {
130 // convert the mesh to the assigned collision object type
131 switch (collision_object_type)
132 {
134 {
135 // Create a convex hull shape to approximate Trimesh
138 std::vector<int> faces;
139
140 input.reserve(geom->vertex_count);
141 for (unsigned int i = 0; i < geom->vertex_count; ++i)
142 input.push_back(Eigen::Vector3d(geom->vertices[3 * i], geom->vertices[3 * i + 1], geom->vertices[3 * i + 2]));
143
144 if (collision_detection_bullet::createConvexHull(vertices, faces, input) < 0)
145 return nullptr;
146
147 btConvexHullShape* subshape = new btConvexHullShape();
148 for (const Eigen::Vector3d& v : vertices)
149 {
150 subshape->addPoint(
151 btVector3(static_cast<btScalar>(v[0]), static_cast<btScalar>(v[1]), static_cast<btScalar>(v[2])));
152 }
153
154 return subshape;
155 }
157 {
158 btCompoundShape* compound =
159 new btCompoundShape(BULLET_COMPOUND_USE_DYNAMIC_AABB, static_cast<int>(geom->triangle_count));
160 compound->setMargin(
161 BULLET_MARGIN); // margin: compound seems to have no effect when positive but has an effect when negative
162
163 for (unsigned i = 0; i < geom->triangle_count; ++i)
164 {
165 btVector3 v[3];
166 for (unsigned x = 0; x < 3; ++x)
167 {
168 unsigned idx = geom->triangles[3 * i + x];
169 for (unsigned y = 0; y < 3; ++y)
170 {
171 v[x][y] = static_cast<btScalar>(geom->vertices[3 * idx + y]);
172 }
173 }
174
175 btCollisionShape* subshape = new btTriangleShapeEx(v[0], v[1], v[2]);
176 if (subshape != nullptr)
177 {
178 cow->manage(subshape);
179 subshape->setMargin(BULLET_MARGIN);
180 btTransform geom_trans;
181 geom_trans.setIdentity();
182 compound->addChildShape(geom_trans, subshape);
183 }
184 }
185
186 return compound;
187 }
188 default:
189 {
190 RCLCPP_ERROR(getLogger(), "This bullet shape type (%d) is not supported for geometry meshs",
191 static_cast<int>(collision_object_type));
192 return nullptr;
193 }
194 }
195 }
196 RCLCPP_ERROR(getLogger(), "The mesh is empty!");
197 return nullptr;
198}
199
200btCollisionShape* createShapePrimitive(const shapes::OcTree* geom, const CollisionObjectType& collision_object_type,
202{
203 assert(collision_object_type == CollisionObjectType::USE_SHAPE_TYPE ||
204 collision_object_type == CollisionObjectType::CONVEX_HULL ||
205 collision_object_type == CollisionObjectType::SDF ||
206 collision_object_type == CollisionObjectType::MULTI_SPHERE);
207
208 btCompoundShape* subshape =
209 new btCompoundShape(BULLET_COMPOUND_USE_DYNAMIC_AABB, static_cast<int>(geom->octree->size()));
210 double occupancy_threshold = geom->octree->getOccupancyThres();
211
212 // convert the mesh to the assigned collision object type
213 switch (collision_object_type)
214 {
216 {
217 for (auto it = geom->octree->begin(static_cast<unsigned char>(geom->octree->getTreeDepth())),
218 end = geom->octree->end();
219 it != end; ++it)
220 {
221 if (it->getOccupancy() >= occupancy_threshold)
222 {
223 double size = it.getSize();
224 btTransform geom_trans;
225 geom_trans.setIdentity();
226 geom_trans.setOrigin(btVector3(static_cast<btScalar>(it.getX()), static_cast<btScalar>(it.getY()),
227 static_cast<btScalar>(it.getZ())));
228 btScalar l = static_cast<btScalar>(size / 2);
229 btBoxShape* childshape = new btBoxShape(btVector3(l, l, l));
230 childshape->setMargin(BULLET_MARGIN);
231 cow->manage(childshape);
232
233 subshape->addChildShape(geom_trans, childshape);
234 }
235 }
236 return subshape;
237 }
239 {
240 for (auto it = geom->octree->begin(static_cast<unsigned char>(geom->octree->getTreeDepth())),
241 end = geom->octree->end();
242 it != end; ++it)
243 {
244 if (it->getOccupancy() >= occupancy_threshold)
245 {
246 double size = it.getSize();
247 btTransform geom_trans;
248 geom_trans.setIdentity();
249 geom_trans.setOrigin(btVector3(static_cast<btScalar>(it.getX()), static_cast<btScalar>(it.getY()),
250 static_cast<btScalar>(it.getZ())));
251 btSphereShape* childshape =
252 new btSphereShape(static_cast<btScalar>(std::sqrt(2 * ((size / 2) * (size / 2)))));
253 childshape->setMargin(BULLET_MARGIN);
254 cow->manage(childshape);
255
256 subshape->addChildShape(geom_trans, childshape);
257 }
258 }
259 return subshape;
260 }
261 default:
262 {
263 RCLCPP_ERROR(getLogger(), "This bullet shape type (%d) is not supported for geometry octree",
264 static_cast<int>(collision_object_type));
265 return nullptr;
266 }
267 }
268}
269
270void updateCollisionObjectFilters(const std::vector<std::string>& active, CollisionObjectWrapper& cow)
271{
272 // if not active make cow part of static
273 if (!isLinkActive(active, cow.getName()))
274 {
275 cow.m_collisionFilterGroup = btBroadphaseProxy::StaticFilter;
276 cow.m_collisionFilterMask = btBroadphaseProxy::KinematicFilter;
277 }
278 else
279 {
280 cow.m_collisionFilterGroup = btBroadphaseProxy::KinematicFilter;
281 cow.m_collisionFilterMask = btBroadphaseProxy::KinematicFilter | btBroadphaseProxy::StaticFilter;
282 }
283
284 if (cow.getBroadphaseHandle())
285 {
286 cow.getBroadphaseHandle()->m_collisionFilterGroup = cow.m_collisionFilterGroup;
287 cow.getBroadphaseHandle()->m_collisionFilterMask = cow.m_collisionFilterMask;
288 }
289 RCLCPP_DEBUG_STREAM(getLogger(), "COW " << cow.getName() << " group " << cow.m_collisionFilterGroup << " mask "
290 << cow.m_collisionFilterMask);
291}
292
293CollisionObjectWrapperPtr makeCastCollisionObject(const CollisionObjectWrapperPtr& cow)
294{
295 CollisionObjectWrapperPtr new_cow = cow->clone();
296
297 btTransform tf;
298 tf.setIdentity();
299
300 if (btBroadphaseProxy::isConvex(new_cow->getCollisionShape()->getShapeType()))
301 {
302 assert(dynamic_cast<btConvexShape*>(new_cow->getCollisionShape()) != nullptr);
303 btConvexShape* convex = static_cast<btConvexShape*>(new_cow->getCollisionShape());
304
305 // This checks if the collision object is already a cast collision object
306 assert(convex->getShapeType() != CUSTOM_CONVEX_SHAPE_TYPE);
307
308 CastHullShape* shape = new CastHullShape(convex, tf);
309
310 new_cow->manage(shape);
311 new_cow->setCollisionShape(shape);
312 }
313 else if (btBroadphaseProxy::isCompound(new_cow->getCollisionShape()->getShapeType()))
314 {
315 btCompoundShape* compound = static_cast<btCompoundShape*>(new_cow->getCollisionShape());
316 btCompoundShape* new_compound =
317 new btCompoundShape(BULLET_COMPOUND_USE_DYNAMIC_AABB, compound->getNumChildShapes());
318
319 for (int i = 0; i < compound->getNumChildShapes(); ++i)
320 {
321 if (btBroadphaseProxy::isConvex(compound->getChildShape(i)->getShapeType()))
322 {
323 btConvexShape* convex = static_cast<btConvexShape*>(compound->getChildShape(i));
324 assert(convex->getShapeType() != CUSTOM_CONVEX_SHAPE_TYPE); // This checks if already a cast collision object
325
326 btTransform geom_trans = compound->getChildTransform(i);
327
328 btCollisionShape* subshape = new CastHullShape(convex, tf);
329
330 new_cow->manage(subshape);
331 subshape->setMargin(BULLET_MARGIN);
332 new_compound->addChildShape(geom_trans, subshape);
333 }
334 else if (btBroadphaseProxy::isCompound(compound->getChildShape(i)->getShapeType()))
335 {
336 btCompoundShape* second_compound = static_cast<btCompoundShape*>(compound->getChildShape(i));
337 btCompoundShape* new_second_compound =
338 new btCompoundShape(BULLET_COMPOUND_USE_DYNAMIC_AABB, second_compound->getNumChildShapes());
339 for (int j = 0; j < second_compound->getNumChildShapes(); ++j)
340 {
341 assert(!btBroadphaseProxy::isCompound(second_compound->getChildShape(j)->getShapeType()));
342
343 btConvexShape* convex = static_cast<btConvexShape*>(second_compound->getChildShape(j));
344 assert(convex->getShapeType() != CUSTOM_CONVEX_SHAPE_TYPE); // This checks if already a cast collision object
345
346 btTransform geom_trans = second_compound->getChildTransform(j);
347
348 btCollisionShape* subshape = new CastHullShape(convex, tf);
349
350 new_cow->manage(subshape);
351 subshape->setMargin(BULLET_MARGIN);
352 new_second_compound->addChildShape(geom_trans, subshape);
353 }
354
355 btTransform geom_trans = compound->getChildTransform(i);
356
357 new_cow->manage(new_second_compound);
358
359 // margin on compound seems to have no effect when positive but has an effect when negative
360 new_second_compound->setMargin(BULLET_MARGIN);
361 new_compound->addChildShape(geom_trans, new_second_compound);
362 }
363 else
364 {
365 RCLCPP_ERROR_STREAM(getLogger(),
366 "I can only collision check convex shapes and compound shapes made of convex shapes");
367 throw std::runtime_error("I can only collision check convex shapes and compound shapes made of convex shapes");
368 }
369 }
370
371 // margin on compound seems to have no effect when positive but has an effect when negative
372 new_compound->setMargin(BULLET_MARGIN);
373 new_cow->manage(new_compound);
374 new_cow->setCollisionShape(new_compound);
375 new_cow->setWorldTransform(cow->getWorldTransform());
376 }
377 else
378 {
379 RCLCPP_ERROR_STREAM(getLogger(),
380 "I can only collision check convex shapes and compound shapes made of convex shapes");
381 throw std::runtime_error("I can only collision check convex shapes and compound shapes made of convex shapes");
382 }
383
384 return new_cow;
385}
386
387void addCollisionObjectToBroadphase(const CollisionObjectWrapperPtr& cow,
388 const std::unique_ptr<btBroadphaseInterface>& broadphase,
389 const std::unique_ptr<btCollisionDispatcher>& dispatcher)
390{
391 RCLCPP_DEBUG_STREAM(getLogger(), "Added " << cow->getName() << " to broadphase");
392 btVector3 aabb_min, aabb_max;
393 cow->getAABB(aabb_min, aabb_max);
394
395 int type = cow->getCollisionShape()->getShapeType();
396 cow->setBroadphaseHandle(broadphase->createProxy(aabb_min, aabb_max, type, cow.get(), cow->m_collisionFilterGroup,
397 cow->m_collisionFilterMask, dispatcher.get()));
398}
399
400btCollisionShape* createShapePrimitive(const shapes::ShapeConstPtr& geom,
401 const CollisionObjectType& collision_object_type, CollisionObjectWrapper* cow)
402{
403 switch (geom->type)
404 {
405 case shapes::BOX:
406 {
407 return createShapePrimitive(static_cast<const shapes::Box*>(geom.get()), collision_object_type);
408 }
409 case shapes::SPHERE:
410 {
411 return createShapePrimitive(static_cast<const shapes::Sphere*>(geom.get()), collision_object_type);
412 }
413 case shapes::CYLINDER:
414 {
415 return createShapePrimitive(static_cast<const shapes::Cylinder*>(geom.get()), collision_object_type);
416 }
417 case shapes::CONE:
418 {
419 return createShapePrimitive(static_cast<const shapes::Cone*>(geom.get()), collision_object_type);
420 }
421 case shapes::MESH:
422 {
423 return createShapePrimitive(static_cast<const shapes::Mesh*>(geom.get()), collision_object_type, cow);
424 }
425 case shapes::OCTREE:
426 {
427 return createShapePrimitive(static_cast<const shapes::OcTree*>(geom.get()), collision_object_type, cow);
428 }
429 default:
430 {
431 RCLCPP_ERROR(getLogger(), "This geometric shape type (%d) is not supported using BULLET yet",
432 static_cast<int>(geom->type));
433 return nullptr;
434 }
435 }
436}
437
438bool BroadphaseFilterCallback::needBroadphaseCollision(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) const
439{
440 bool cull = !(proxy0->m_collisionFilterMask & proxy1->m_collisionFilterGroup);
441 cull = cull || !(proxy1->m_collisionFilterMask & proxy0->m_collisionFilterGroup);
442
443 if (cull)
444 return false;
445
446 const CollisionObjectWrapper* cow0 = static_cast<const CollisionObjectWrapper*>(proxy0->m_clientObject);
447 const CollisionObjectWrapper* cow1 = static_cast<const CollisionObjectWrapper*>(proxy1->m_clientObject);
448
449 if (!cow0->m_enabled)
450 return false;
451
452 if (!cow1->m_enabled)
453 return false;
454
455 if (cow0->getTypeID() == collision_detection::BodyType::ROBOT_ATTACHED &&
456 cow1->getTypeID() == collision_detection::BodyType::ROBOT_LINK)
457 {
458 if (cow0->touch_links.find(cow1->getName()) != cow0->touch_links.end())
459 return false;
460 }
461
462 if (cow1->getTypeID() == collision_detection::BodyType::ROBOT_ATTACHED &&
463 cow0->getTypeID() == collision_detection::BodyType::ROBOT_LINK)
464 {
465 if (cow1->touch_links.find(cow0->getName()) != cow1->touch_links.end())
466 return false;
467 }
468
469 if (cow0->getTypeID() == collision_detection::BodyType::ROBOT_ATTACHED &&
470 cow1->getTypeID() == collision_detection::BodyType::ROBOT_ATTACHED)
471 {
472 if (cow0->touch_links == cow1->touch_links)
473 return false;
474 }
475
476 RCLCPP_DEBUG_STREAM(getLogger(), "Broadphase pass " << cow0->getName() << " vs " << cow1->getName());
477 return true;
478}
479
481 const btCollisionObjectWrapper* colObj0Wrap, int /*partId0*/,
482 int index0, const btCollisionObjectWrapper* colObj1Wrap,
483 int /*partId1*/, int index1)
484{
485 if (cp.m_distance1 > static_cast<btScalar>(contact_distance_))
486 {
487 RCLCPP_DEBUG_STREAM(getLogger(), "Not close enough for collision with " << cp.m_distance1);
488 return 0;
489 }
490
491 if (cast_)
492 {
493 return addCastSingleResult(cp, colObj0Wrap, index0, colObj1Wrap, index1, collisions_);
494 }
495 else
496 {
497 return addDiscreteSingleResult(cp, colObj0Wrap, colObj1Wrap, collisions_);
498 }
499}
500
502{
503 results_callback_.collisions_.pair_done = false;
504
505 if (results_callback_.collisions_.done)
506 {
507 return false;
508 }
509
510 const CollisionObjectWrapper* cow0 = static_cast<const CollisionObjectWrapper*>(pair.m_pProxy0->m_clientObject);
511 const CollisionObjectWrapper* cow1 = static_cast<const CollisionObjectWrapper*>(pair.m_pProxy1->m_clientObject);
512
513 std::pair<std::string, std::string> pair_names{ cow0->getName(), cow1->getName() };
514 if (results_callback_.needsCollision(cow0, cow1))
515 {
516 RCLCPP_DEBUG_STREAM(getLogger(), "Processing " << cow0->getName() << " vs " << cow1->getName());
517 btCollisionObjectWrapper obj0_wrap(nullptr, cow0->getCollisionShape(), cow0, cow0->getWorldTransform(), -1, -1);
518 btCollisionObjectWrapper obj1_wrap(nullptr, cow1->getCollisionShape(), cow1, cow1->getWorldTransform(), -1, -1);
519
520 // dispatcher will keep algorithms persistent in the collision pair
521 if (!pair.m_algorithm)
522 {
523 pair.m_algorithm = dispatcher_->findAlgorithm(&obj0_wrap, &obj1_wrap, nullptr, BT_CLOSEST_POINT_ALGORITHMS);
524 }
525
526 if (pair.m_algorithm)
527 {
528 TesseractBroadphaseBridgedManifoldResult contact_point_result(&obj0_wrap, &obj1_wrap, results_callback_);
529 contact_point_result.m_closestPointDistanceThreshold = static_cast<btScalar>(results_callback_.contact_distance_);
530
531 // discrete collision detection query
532 pair.m_algorithm->processCollision(&obj0_wrap, &obj1_wrap, dispatch_info_, &contact_point_result);
533 }
534 }
535 else
536 {
537 RCLCPP_DEBUG_STREAM(getLogger(), "Not processing " << cow0->getName() << " vs " << cow1->getName());
538 }
539 return false;
540}
541
543 const std::vector<shapes::ShapeConstPtr>& shapes,
544 const AlignedVector<Eigen::Isometry3d>& shape_poses,
545 const std::vector<CollisionObjectType>& collision_object_types,
546 bool active)
547 : name_(name)
548 , type_id_(type_id)
549 , shapes_(shapes)
550 , shape_poses_(shape_poses)
551 , collision_object_types_(collision_object_types)
552{
553 if (shapes.empty() || shape_poses.empty() ||
554 (shapes.size() != shape_poses.size() || collision_object_types.empty() ||
555 shapes.size() != collision_object_types.size()))
556 {
557 throw std::exception();
558 }
559
560 setContactProcessingThreshold(BULLET_DEFAULT_CONTACT_DISTANCE);
561 assert(!name.empty());
562
563 if (active)
564 {
565 m_collisionFilterGroup = btBroadphaseProxy::KinematicFilter;
566 m_collisionFilterMask = btBroadphaseProxy::KinematicFilter | btBroadphaseProxy::StaticFilter;
567 }
568 else
569 {
570 m_collisionFilterGroup = btBroadphaseProxy::StaticFilter;
571 m_collisionFilterMask = btBroadphaseProxy::KinematicFilter;
572 }
573
574 if (shapes.size() == 1)
575 {
576 btCollisionShape* shape = createShapePrimitive(shapes_[0], collision_object_types[0], this);
577 shape->setMargin(BULLET_MARGIN);
578 manage(shape);
579 setCollisionShape(shape);
580 setWorldTransform(convertEigenToBt(shape_poses_[0]));
581 }
582 else
583 {
584 btCompoundShape* compound = new btCompoundShape(BULLET_COMPOUND_USE_DYNAMIC_AABB, static_cast<int>(shapes_.size()));
585 manage(compound);
586 // margin on compound seems to have no effect when positive but has an effect when negative
587 compound->setMargin(BULLET_MARGIN);
588 setCollisionShape(compound);
589
590 setWorldTransform(convertEigenToBt(shape_poses_[0]));
591 Eigen::Isometry3d inv_world = shape_poses_[0].inverse();
592
593 for (std::size_t j = 0; j < shapes_.size(); ++j)
594 {
595 btCollisionShape* subshape = createShapePrimitive(shapes_[j], collision_object_types[j], this);
596 if (subshape != nullptr)
597 {
598 manage(subshape);
599 subshape->setMargin(BULLET_MARGIN);
600 btTransform geom_trans = convertEigenToBt(inv_world * shape_poses_[j]);
601 compound->addChildShape(geom_trans, subshape);
602 }
603 }
604 }
605}
606
608 const std::vector<shapes::ShapeConstPtr>& shapes,
609 const AlignedVector<Eigen::Isometry3d>& shape_poses,
610 const std::vector<CollisionObjectType>& collision_object_types,
611 const std::set<std::string>& touch_links)
612 : CollisionObjectWrapper(name, type_id, shapes, shape_poses, collision_object_types, true)
613{
614 this->touch_links = touch_links;
615}
616
618 const std::vector<shapes::ShapeConstPtr>& shapes,
619 const AlignedVector<Eigen::Isometry3d>& shape_poses,
620 const std::vector<CollisionObjectType>& collision_object_types,
621 const std::vector<std::shared_ptr<void>>& data)
622 : name_(name)
623 , type_id_(type_id)
624 , shapes_(shapes)
625 , shape_poses_(shape_poses)
626 , collision_object_types_(collision_object_types)
627 , data_(data)
628{
629}
630} // namespace collision_detection_bullet
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
bool getAllowedCollision(const std::string &name1, const std::string &name2, DecideContactFn &fn) const
Get the allowed collision predicate between two elements. Return true if a predicate for entry is inc...
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.
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.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionObjectWrapper(const std::string &name, const collision_detection::BodyType &type_id, const std::vector< shapes::ShapeConstPtr > &shapes, const AlignedVector< Eigen::Isometry3d > &shape_poses, const std::vector< CollisionObjectType > &collision_object_types, bool active=true)
Standard constructor.
const std::string & getName() const
Get the collision object name.
short int m_collisionFilterMask
Bitfield specifies against which other groups the object is collision checked.
bool processOverlap(btBroadphasePair &pair) override
@ NEVER
Collisions between the pair of bodies is never ok, i.e., if two bodies are in contact in a particular...
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)
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.
const bool BULLET_COMPOUND_USE_DYNAMIC_AABB
btScalar addCastSingleResult(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int, const btCollisionObjectWrapper *colObj1Wrap, int, ContactTestData &collisions)
void addCollisionObjectToBroadphase(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Add the collision object to broadphase.
@ MULTI_SPHERE
Use the mesh and represent it by multiple spheres collision object.
@ SDF
Use the mesh and rpresent it by a signed distance fields collision object.
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
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.
bool isLinkActive(const std::vector< std::string > &active, const std::string &name)
This will check if a link is active provided a list. If the list is empty the link is considered acti...
int createConvexHull(AlignedVector< Eigen::Vector3d > &vertices, std::vector< int > &faces, const AlignedVector< Eigen::Vector3d > &input, double shrink=-1, double shrinkClamp=-1)
Create a convex hull from vertices using Bullet Convex Hull Computer.
Definition world.h:49
KeyboardReader input
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 ...
bool cast_
Indicates if the callback is used for casted collisions.
bool needBroadphaseCollision(btBroadphaseProxy *proxy0, btBroadphaseProxy *proxy1) const override
Casted collision shape used for checking if an object is collision free between two discrete poses.
bool done
Indicates if search is finished.
Definition basic_types.h:77
bool pair_done
Indicates if search between a single pair is finished.
Definition basic_types.h:80