-
Notifications
You must be signed in to change notification settings - Fork 288
/
Copy pathBulletCollisionDetector.cpp
1046 lines (872 loc) · 36.5 KB
/
BulletCollisionDetector.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright (c) 2011-2024, The DART development contributors
* All rights reserved.
*
* The list of contributors can be found at:
* https://github.com/dartsim/dart/blob/main/LICENSE
*
* This file is provided under the following "BSD-style" License:
* Redistribution and use in source and binary forms, with or
* without modification, are permitted provided that the following
* conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include "dart/collision/bullet/BulletCollisionDetector.hpp"
#include "dart/collision/CollisionFilter.hpp"
#include "dart/collision/CollisionObject.hpp"
#include "dart/collision/bullet/BulletCollisionGroup.hpp"
#include "dart/collision/bullet/BulletCollisionObject.hpp"
#include "dart/collision/bullet/BulletInclude.hpp"
#include "dart/collision/bullet/BulletTypes.hpp"
#include "dart/collision/bullet/detail/BulletCollisionDispatcher.hpp"
#include "dart/collision/bullet/detail/BulletOverlapFilterCallback.hpp"
#include "dart/common/Console.hpp"
#include "dart/dynamics/BoxShape.hpp"
#include "dart/dynamics/CapsuleShape.hpp"
#include "dart/dynamics/ConeShape.hpp"
#include "dart/dynamics/CylinderShape.hpp"
#include "dart/dynamics/EllipsoidShape.hpp"
#include "dart/dynamics/HeightmapShape.hpp"
#include "dart/dynamics/MeshShape.hpp"
#include "dart/dynamics/MultiSphereConvexHullShape.hpp"
#include "dart/dynamics/PlaneShape.hpp"
#include "dart/dynamics/Shape.hpp"
#include "dart/dynamics/ShapeFrame.hpp"
#include "dart/dynamics/SoftMeshShape.hpp"
#include "dart/dynamics/SphereShape.hpp"
#include <algorithm>
namespace dart {
namespace collision {
namespace {
Contact convertContact(
const btManifoldPoint& bulletManifoldPoint,
BulletCollisionObject* collObj1,
BulletCollisionObject* collObj2);
void reportContacts(
btCollisionWorld* collWorld,
const CollisionOption& option,
CollisionResult& result);
void reportRayHits(
const btCollisionWorld::ClosestRayResultCallback callback,
const RaycastOption& option,
RaycastResult& result);
void reportRayHits(
const btCollisionWorld::AllHitsRayResultCallback callback,
const RaycastOption& option,
RaycastResult& result);
std::unique_ptr<btCollisionShape> createBulletEllipsoidMesh(
float sizeX, float sizeY, float sizeZ);
std::unique_ptr<btCollisionShape> createBulletCollisionShapeFromAssimpScene(
const Eigen::Vector3d& scale, const aiScene* scene);
std::unique_ptr<btCollisionShape> createBulletCollisionShapeFromAssimpMesh(
const aiMesh* mesh);
template <typename HeightmapShapeT>
std::unique_ptr<BulletCollisionShape> createBulletCollisionShapeFromHeightmap(
const HeightmapShapeT* heightMap);
bool isConvex(const aiMesh* mesh, float threshold = 0.001);
} // anonymous namespace
//==============================================================================
BulletCollisionDetector::Registrar<BulletCollisionDetector>
BulletCollisionDetector::mRegistrar{
BulletCollisionDetector::getStaticType(),
[]() -> std::shared_ptr<dart::collision::BulletCollisionDetector> {
return dart::collision::BulletCollisionDetector::create();
}};
//==============================================================================
std::shared_ptr<BulletCollisionDetector> BulletCollisionDetector::create()
{
return std::shared_ptr<BulletCollisionDetector>(
new BulletCollisionDetector());
}
//==============================================================================
BulletCollisionDetector::~BulletCollisionDetector()
{
assert(mShapeMap.empty());
}
//==============================================================================
std::shared_ptr<CollisionDetector>
BulletCollisionDetector::cloneWithoutCollisionObjects() const
{
return BulletCollisionDetector::create();
}
//==============================================================================
const std::string& BulletCollisionDetector::getType() const
{
return getStaticType();
}
//==============================================================================
const std::string& BulletCollisionDetector::getStaticType()
{
static const std::string type = "bullet";
return type;
}
//==============================================================================
std::unique_ptr<CollisionGroup> BulletCollisionDetector::createCollisionGroup()
{
return std::make_unique<BulletCollisionGroup>(shared_from_this());
}
//==============================================================================
static bool checkGroupValidity(
BulletCollisionDetector* cd, CollisionGroup* group)
{
if (cd != group->getCollisionDetector().get()) {
dterr << "[BulletCollisionDetector::collide] Attempting to check collision "
<< "for a collision group that is created from a different collision "
<< "detector instance.\n";
return false;
}
return true;
}
//==============================================================================
static bool isCollision(btCollisionWorld* world)
{
assert(world);
auto dispatcher = world->getDispatcher();
assert(dispatcher);
const auto numManifolds = dispatcher->getNumManifolds();
for (auto i = 0; i < numManifolds; ++i) {
const auto* contactManifold = dispatcher->getManifoldByIndexInternal(i);
if (contactManifold->getNumContacts() > 0)
return true;
}
return false;
}
//==============================================================================
void filterOutCollisions(btCollisionWorld* world)
{
assert(world);
auto dispatcher
= static_cast<detail::BulletCollisionDispatcher*>(world->getDispatcher());
assert(dispatcher);
const auto filter = dispatcher->getFilter();
if (!filter)
return;
const auto numManifolds = dispatcher->getNumManifolds();
std::vector<btPersistentManifold*> manifoldsToRelease;
for (auto i = 0; i < numManifolds; ++i) {
const auto contactManifold = dispatcher->getManifoldByIndexInternal(i);
const auto body0 = contactManifold->getBody0();
const auto body1 = contactManifold->getBody1();
const auto userPtr0 = body0->getUserPointer();
const auto userPtr1 = body1->getUserPointer();
const auto collObj0 = static_cast<BulletCollisionObject*>(userPtr0);
const auto collObj1 = static_cast<BulletCollisionObject*>(userPtr1);
if (filter->ignoresCollision(collObj0, collObj1))
manifoldsToRelease.push_back(contactManifold);
}
for (const auto& manifold : manifoldsToRelease)
dispatcher->clearManifold(manifold);
}
//==============================================================================
bool BulletCollisionDetector::collide(
CollisionGroup* group,
const CollisionOption& option,
CollisionResult* result)
{
if (result)
result->clear();
if (0u == option.maxNumContacts)
return false;
// Check if 'this' is the collision engine of 'group'.
if (!checkGroupValidity(this, group))
return false;
auto castedGroup = static_cast<BulletCollisionGroup*>(group);
auto collisionWorld = castedGroup->getBulletCollisionWorld();
auto dispatcher = static_cast<detail::BulletCollisionDispatcher*>(
collisionWorld->getDispatcher());
dispatcher->setFilter(option.collisionFilter);
// Filter out persistent contact pairs already existing in the world
filterOutCollisions(collisionWorld);
castedGroup->updateEngineData();
collisionWorld->performDiscreteCollisionDetection();
if (result) {
reportContacts(collisionWorld, option, *result);
return result->isCollision();
} else {
return isCollision(collisionWorld);
}
}
//==============================================================================
bool BulletCollisionDetector::collide(
CollisionGroup* group1,
CollisionGroup* group2,
const CollisionOption& option,
CollisionResult* result)
{
if (result)
result->clear();
if (0u == option.maxNumContacts)
return false;
if (!checkGroupValidity(this, group1))
return false;
if (!checkGroupValidity(this, group2))
return false;
// Create a new collision group, merging the two groups into
mGroupForFiltering.reset(new BulletCollisionGroup(shared_from_this()));
auto bulletCollisionWorld = mGroupForFiltering->getBulletCollisionWorld();
auto bulletPairCache = bulletCollisionWorld->getPairCache();
auto filterCallback = new detail::BulletOverlapFilterCallback(
option.collisionFilter, group1, group2);
bulletPairCache->setOverlapFilterCallback(filterCallback);
mGroupForFiltering->addShapeFramesOf(group1, group2);
mGroupForFiltering->updateEngineData();
bulletCollisionWorld->performDiscreteCollisionDetection();
if (result) {
reportContacts(bulletCollisionWorld, option, *result);
return result->isCollision();
} else {
return isCollision(bulletCollisionWorld);
}
}
//==============================================================================
double BulletCollisionDetector::distance(
CollisionGroup* /*group*/,
const DistanceOption& /*option*/,
DistanceResult* /*result*/)
{
static bool warned = false;
if (!warned) {
dtwarn
<< "[BulletCollisionDetector::distance] This collision detector does "
<< "not support (signed) distance queries. Returning 0.0.\n";
warned = true;
}
return 0.0;
}
//==============================================================================
double BulletCollisionDetector::distance(
CollisionGroup* /*group1*/,
CollisionGroup* /*group2*/,
const DistanceOption& /*option*/,
DistanceResult* /*result*/)
{
static bool warned = false;
if (!warned) {
dtwarn
<< "[BulletCollisionDetector::distance] This collision detector does "
<< "not support (signed) distance queries. Returning.\n";
warned = true;
}
return 0.0;
}
//==============================================================================
bool BulletCollisionDetector::raycast(
CollisionGroup* group,
const Eigen::Vector3d& from,
const Eigen::Vector3d& to,
const RaycastOption& option,
RaycastResult* result)
{
if (result)
result->clear();
// Check if 'this' is the collision engine of 'group'.
if (!checkGroupValidity(this, group))
return false;
auto castedGroup = static_cast<BulletCollisionGroup*>(group);
auto collisionWorld = castedGroup->getBulletCollisionWorld();
const auto btFrom = convertVector3(from);
const auto btTo = convertVector3(to);
if (option.mEnableAllHits) {
auto callback = btCollisionWorld::AllHitsRayResultCallback(btFrom, btTo);
castedGroup->updateEngineData();
collisionWorld->rayTest(btFrom, btTo, callback);
if (result == nullptr)
return callback.hasHit();
if (callback.hasHit()) {
reportRayHits(callback, option, *result);
return result->hasHit();
} else {
return false;
}
} else {
auto callback = btCollisionWorld::ClosestRayResultCallback(btFrom, btTo);
castedGroup->updateEngineData();
collisionWorld->rayTest(btFrom, btTo, callback);
if (result == nullptr)
return callback.hasHit();
if (callback.hasHit()) {
reportRayHits(callback, option, *result);
return result->hasHit();
} else {
return false;
}
}
}
//==============================================================================
BulletCollisionDetector::BulletCollisionDetector() : CollisionDetector()
{
mCollisionObjectManager.reset(new ManagerForUnsharableCollisionObjects(this));
}
//==============================================================================
std::unique_ptr<CollisionObject> BulletCollisionDetector::createCollisionObject(
const dynamics::ShapeFrame* shapeFrame)
{
auto bulletCollShape = claimBulletCollisionShape(shapeFrame->getShape());
return std::unique_ptr<BulletCollisionObject>(
new BulletCollisionObject(this, shapeFrame, bulletCollShape));
}
//==============================================================================
void BulletCollisionDetector::refreshCollisionObject(CollisionObject* object)
{
BulletCollisionObject* bullet = static_cast<BulletCollisionObject*>(object);
bullet->mBulletCollisionShape = claimBulletCollisionShape(bullet->getShape());
bullet->mBulletCollisionObject->setCollisionShape(
bullet->mBulletCollisionShape->mCollisionShape.get());
}
//==============================================================================
void BulletCollisionDetector::notifyCollisionObjectDestroying(
CollisionObject* object)
{
reclaimBulletCollisionShape(object->getShape());
}
//==============================================================================
std::shared_ptr<BulletCollisionShape>
BulletCollisionDetector::claimBulletCollisionShape(
const dynamics::ConstShapePtr& shape)
{
const std::size_t currentVersion = shape->getVersion();
const auto search = mShapeMap.insert(std::make_pair(shape, ShapeInfo()));
const bool inserted = search.second;
ShapeInfo& info = search.first->second;
if (!inserted && currentVersion == info.mLastKnownVersion) {
const auto& bulletCollShape = info.mShape.lock();
assert(bulletCollShape);
return bulletCollShape;
}
auto newBulletCollisionShape = std::shared_ptr<BulletCollisionShape>(
createBulletCollisionShape(shape).release(),
BulletCollisionShapeDeleter(this, shape));
info.mShape = newBulletCollisionShape;
info.mLastKnownVersion = currentVersion;
return newBulletCollisionShape;
}
//==============================================================================
void BulletCollisionDetector::reclaimBulletCollisionShape(
const dynamics::ConstShapePtr& shape)
{
const auto& search = mShapeMap.find(shape);
if (search == mShapeMap.end())
return;
const auto& bulletShape = search->second.mShape.lock();
if (!bulletShape || bulletShape.use_count() <= 2)
mShapeMap.erase(search);
}
//==============================================================================
std::unique_ptr<BulletCollisionShape>
BulletCollisionDetector::createBulletCollisionShape(
const dynamics::ConstShapePtr& shape)
{
using dynamics::BoxShape;
using dynamics::CapsuleShape;
using dynamics::ConeShape;
using dynamics::CylinderShape;
using dynamics::EllipsoidShape;
using dynamics::HeightmapShaped;
using dynamics::HeightmapShapef;
using dynamics::MeshShape;
using dynamics::MultiSphereConvexHullShape;
using dynamics::PlaneShape;
using dynamics::Shape;
using dynamics::SoftMeshShape;
using dynamics::SphereShape;
if (const auto sphere = shape->as<SphereShape>()) {
const auto radius = sphere->getRadius();
auto bulletCollisionShape = std::make_unique<btSphereShape>(radius);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto box = shape->as<BoxShape>()) {
const Eigen::Vector3d& size = box->getSize();
auto bulletCollisionShape
= std::make_unique<btBoxShape>(convertVector3(size * 0.5));
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto ellipsoid = shape->as<EllipsoidShape>()) {
const Eigen::Vector3d& radii = ellipsoid->getRadii();
auto bulletCollisionShape = createBulletEllipsoidMesh(
radii[0] * 2.0, radii[1] * 2.0, radii[2] * 2.0);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto cylinder = shape->as<CylinderShape>()) {
const auto radius = cylinder->getRadius();
const auto height = cylinder->getHeight();
const auto size = btVector3(radius, radius, height * 0.5);
auto bulletCollisionShape = std::make_unique<btCylinderShapeZ>(size);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto capsule = shape->as<CapsuleShape>()) {
const auto radius = capsule->getRadius();
const auto height = capsule->getHeight();
auto bulletCollisionShape
= std::make_unique<btCapsuleShapeZ>(radius, height);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto cone = shape->as<ConeShape>()) {
const auto radius = cone->getRadius();
const auto height = cone->getHeight();
auto bulletCollisionShape = std::make_unique<btConeShapeZ>(radius, height);
bulletCollisionShape->setMargin(0.0);
// TODO(JS): Bullet seems to use constant margin 0.4, however this could be
// dangerous when the cone is sufficiently small. We use zero margin here
// until find better solution even using zero margin is not recommended:
// https://www.sjbaker.org/wiki/index.php?title=Physics_-_Bullet_Collected_random_advice#Minimum_object_sizes_-_by_Erwin
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto plane = shape->as<PlaneShape>()) {
const Eigen::Vector3d normal = plane->getNormal();
const double offset = plane->getOffset();
auto bulletCollisionShape
= std::make_unique<btStaticPlaneShape>(convertVector3(normal), offset);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto multiSphere = shape->as<MultiSphereConvexHullShape>()) {
const auto numSpheres = multiSphere->getNumSpheres();
const auto& spheres = multiSphere->getSpheres();
std::vector<btVector3> bulletPositions(numSpheres);
std::vector<btScalar> bulletRadii(numSpheres);
for (auto i = 0u; i < numSpheres; ++i) {
bulletRadii[i] = static_cast<btScalar>(spheres[i].first);
bulletPositions[i] = convertVector3(spheres[i].second);
}
auto bulletCollisionShape = std::make_unique<btMultiSphereShape>(
bulletPositions.data(), bulletRadii.data(), numSpheres);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto shapeMesh = shape->as<MeshShape>()) {
const auto scale = shapeMesh->getScale();
const auto mesh = shapeMesh->getMesh();
auto bulletCollisionShape
= createBulletCollisionShapeFromAssimpScene(scale, mesh);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto softMeshShape = shape->as<SoftMeshShape>()) {
const auto mesh = softMeshShape->getAssimpMesh();
auto bulletCollisionShape = createBulletCollisionShapeFromAssimpMesh(mesh);
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
} else if (const auto heightMap = shape->as<HeightmapShapef>()) {
return createBulletCollisionShapeFromHeightmap(heightMap);
} else if (shape->is<HeightmapShaped>()) {
assert(dynamic_cast<const HeightmapShaped*>(shape.get()));
dterr << "[BulletCollisionDetector::createBulletCollisionShape] "
<< "Bullet does not support double height fields (shape type ["
<< shape->getType() << "]). Creating a sphere with 0.1 radius "
<< "instead.\n";
return std::make_unique<BulletCollisionShape>(
std::make_unique<btSphereShape>(0.1));
// take this back in as soon as bullet supports double in heightmaps
// const auto heightMap = static_cast<const HeightmapShaped*>(shape.get());
// return createBulletCollisionShapeFromHeightmap(heightMap);
} else {
dterr << "[BulletCollisionDetector::createBulletCollisionShape] "
<< "Attempting to create an unsupported shape type ["
<< shape->getType() << "] Creating a sphere with 0.1 radius "
<< "instead.\n";
return std::make_unique<BulletCollisionShape>(
std::make_unique<btSphereShape>(0.1));
}
}
//==============================================================================
BulletCollisionDetector::BulletCollisionShapeDeleter ::
BulletCollisionShapeDeleter(
BulletCollisionDetector* cd, const dynamics::ConstShapePtr& shape)
: mBulletCollisionDetector(cd), mShape(shape)
{
// Do nothing
}
//==============================================================================
void BulletCollisionDetector::BulletCollisionShapeDeleter ::operator()(
BulletCollisionShape* shape) const
{
mBulletCollisionDetector->reclaimBulletCollisionShape(mShape);
delete shape;
}
namespace {
//==============================================================================
Contact convertContact(
const btManifoldPoint& bulletManifoldPoint,
BulletCollisionObject* collObj1,
BulletCollisionObject* collObj2)
{
assert(collObj1);
assert(collObj2);
Contact contact;
contact.point = convertVector3(bulletManifoldPoint.getPositionWorldOnA());
contact.normal = convertVector3(bulletManifoldPoint.m_normalWorldOnB);
contact.penetrationDepth = -bulletManifoldPoint.m_distance1;
contact.collisionObject1 = collObj1;
contact.collisionObject2 = collObj2;
return contact;
}
//==============================================================================
void reportContacts(
btCollisionWorld* world,
const CollisionOption& option,
CollisionResult& result)
{
assert(world);
auto dispatcher
= static_cast<detail::BulletCollisionDispatcher*>(world->getDispatcher());
assert(dispatcher);
const auto numManifolds = dispatcher->getNumManifolds();
for (auto i = 0; i < numManifolds; ++i) {
const auto contactManifold = dispatcher->getManifoldByIndexInternal(i);
const auto body0 = contactManifold->getBody0();
const auto body1 = contactManifold->getBody1();
const auto userPointer0 = body0->getUserPointer();
const auto userPointer1 = body1->getUserPointer();
const auto collObj0 = static_cast<BulletCollisionObject*>(userPointer0);
const auto collObj1 = static_cast<BulletCollisionObject*>(userPointer1);
const auto numContacts = contactManifold->getNumContacts();
for (auto j = 0; j < numContacts; ++j) {
const auto& cp = contactManifold->getContactPoint(j);
if (cp.m_normalWorldOnB.length2() < Contact::getNormalEpsilonSquared()) {
// Skip this contact. This is because we assume that a contact with
// zero-length normal is invalid.
continue;
}
result.addContact(convertContact(cp, collObj0, collObj1));
// No need to check further collisions
if (result.getNumContacts() >= option.maxNumContacts) {
dispatcher->setDone(true);
return;
}
}
}
}
//==============================================================================
RayHit convertRayHit(
const btCollisionObject* btCollObj,
btVector3 hitPointWorld,
btVector3 hitNormalWorld,
btScalar closestHitFraction)
{
RayHit rayHit;
assert(btCollObj);
const auto* userPointer = btCollObj->getUserPointer();
assert(userPointer);
const auto* collObj = static_cast<const BulletCollisionObject*>(userPointer);
assert(collObj);
rayHit.mCollisionObject = collObj;
rayHit.mPoint = convertVector3(hitPointWorld);
rayHit.mNormal = convertVector3(hitNormalWorld);
rayHit.mFraction = static_cast<double>(closestHitFraction);
return rayHit;
}
//==============================================================================
void reportRayHits(
const btCollisionWorld::ClosestRayResultCallback callback,
const RaycastOption& /*option*/,
RaycastResult& result)
{
// This function shouldn't be called if callback has not ray hit.
assert(callback.hasHit());
const auto rayHit = convertRayHit(
callback.m_collisionObject,
callback.m_hitPointWorld,
callback.m_hitNormalWorld,
callback.m_closestHitFraction);
result.mRayHits.clear();
result.mRayHits.reserve(1);
result.mRayHits.emplace_back(rayHit);
}
//==============================================================================
struct FractionLess
{
bool operator()(const RayHit& a, const RayHit& b)
{
return a.mFraction < b.mFraction;
}
};
//==============================================================================
void reportRayHits(
const btCollisionWorld::AllHitsRayResultCallback callback,
const RaycastOption& option,
RaycastResult& result)
{
result.mRayHits.clear();
result.mRayHits.reserve(
static_cast<std::size_t>(callback.m_hitPointWorld.size()));
for (auto i = 0; i < callback.m_hitPointWorld.size(); ++i) {
const auto rayHit = convertRayHit(
callback.m_collisionObjects[i],
callback.m_hitPointWorld[i],
callback.m_hitNormalWorld[i],
callback.m_hitFractions[i]);
result.mRayHits.emplace_back(rayHit);
}
if (option.mSortByClosest)
std::sort(result.mRayHits.begin(), result.mRayHits.end(), FractionLess());
}
//==============================================================================
std::unique_ptr<btCollisionShape> createBulletEllipsoidMesh(
float sizeX, float sizeY, float sizeZ)
{
float v[59][3]
= {{0, 0, 0},
{0.135299, -0.461940, -0.135299},
{0.000000, -0.461940, -0.191342},
{-0.135299, -0.461940, -0.135299},
{-0.191342, -0.461940, 0.000000},
{-0.135299, -0.461940, 0.135299},
{0.000000, -0.461940, 0.191342},
{0.135299, -0.461940, 0.135299},
{0.191342, -0.461940, 0.000000},
{0.250000, -0.353553, -0.250000},
{0.000000, -0.353553, -0.353553},
{-0.250000, -0.353553, -0.250000},
{-0.353553, -0.353553, 0.000000},
{-0.250000, -0.353553, 0.250000},
{0.000000, -0.353553, 0.353553},
{0.250000, -0.353553, 0.250000},
{0.353553, -0.353553, 0.000000},
{0.326641, -0.191342, -0.326641},
{0.000000, -0.191342, -0.461940},
{-0.326641, -0.191342, -0.326641},
{-0.461940, -0.191342, 0.000000},
{-0.326641, -0.191342, 0.326641},
{0.000000, -0.191342, 0.461940},
{0.326641, -0.191342, 0.326641},
{0.461940, -0.191342, 0.000000},
{0.353553, 0.000000, -0.353553},
{0.000000, 0.000000, -0.500000},
{-0.353553, 0.000000, -0.353553},
{-0.500000, 0.000000, 0.000000},
{-0.353553, 0.000000, 0.353553},
{0.000000, 0.000000, 0.500000},
{0.353553, 0.000000, 0.353553},
{0.500000, 0.000000, 0.000000},
{0.326641, 0.191342, -0.326641},
{0.000000, 0.191342, -0.461940},
{-0.326641, 0.191342, -0.326641},
{-0.461940, 0.191342, 0.000000},
{-0.326641, 0.191342, 0.326641},
{0.000000, 0.191342, 0.461940},
{0.326641, 0.191342, 0.326641},
{0.461940, 0.191342, 0.000000},
{0.250000, 0.353553, -0.250000},
{0.000000, 0.353553, -0.353553},
{-0.250000, 0.353553, -0.250000},
{-0.353553, 0.353553, 0.000000},
{-0.250000, 0.353553, 0.250000},
{0.000000, 0.353553, 0.353553},
{0.250000, 0.353553, 0.250000},
{0.353553, 0.353553, 0.000000},
{0.135299, 0.461940, -0.135299},
{0.000000, 0.461940, -0.191342},
{-0.135299, 0.461940, -0.135299},
{-0.191342, 0.461940, 0.000000},
{-0.135299, 0.461940, 0.135299},
{0.000000, 0.461940, 0.191342},
{0.135299, 0.461940, 0.135299},
{0.191342, 0.461940, 0.000000},
{0.000000, -0.500000, 0.000000},
{0.000000, 0.500000, 0.000000}};
int f[112][3]
= {{1, 2, 9}, {9, 2, 10}, {2, 3, 10}, {10, 3, 11}, {3, 4, 11},
{11, 4, 12}, {4, 5, 12}, {12, 5, 13}, {5, 6, 13}, {13, 6, 14},
{6, 7, 14}, {14, 7, 15}, {7, 8, 15}, {15, 8, 16}, {8, 1, 16},
{16, 1, 9}, {9, 10, 17}, {17, 10, 18}, {10, 11, 18}, {18, 11, 19},
{11, 12, 19}, {19, 12, 20}, {12, 13, 20}, {20, 13, 21}, {13, 14, 21},
{21, 14, 22}, {14, 15, 22}, {22, 15, 23}, {15, 16, 23}, {23, 16, 24},
{16, 9, 24}, {24, 9, 17}, {17, 18, 25}, {25, 18, 26}, {18, 19, 26},
{26, 19, 27}, {19, 20, 27}, {27, 20, 28}, {20, 21, 28}, {28, 21, 29},
{21, 22, 29}, {29, 22, 30}, {22, 23, 30}, {30, 23, 31}, {23, 24, 31},
{31, 24, 32}, {24, 17, 32}, {32, 17, 25}, {25, 26, 33}, {33, 26, 34},
{26, 27, 34}, {34, 27, 35}, {27, 28, 35}, {35, 28, 36}, {28, 29, 36},
{36, 29, 37}, {29, 30, 37}, {37, 30, 38}, {30, 31, 38}, {38, 31, 39},
{31, 32, 39}, {39, 32, 40}, {32, 25, 40}, {40, 25, 33}, {33, 34, 41},
{41, 34, 42}, {34, 35, 42}, {42, 35, 43}, {35, 36, 43}, {43, 36, 44},
{36, 37, 44}, {44, 37, 45}, {37, 38, 45}, {45, 38, 46}, {38, 39, 46},
{46, 39, 47}, {39, 40, 47}, {47, 40, 48}, {40, 33, 48}, {48, 33, 41},
{41, 42, 49}, {49, 42, 50}, {42, 43, 50}, {50, 43, 51}, {43, 44, 51},
{51, 44, 52}, {44, 45, 52}, {52, 45, 53}, {45, 46, 53}, {53, 46, 54},
{46, 47, 54}, {54, 47, 55}, {47, 48, 55}, {55, 48, 56}, {48, 41, 56},
{56, 41, 49}, {2, 1, 57}, {3, 2, 57}, {4, 3, 57}, {5, 4, 57},
{6, 5, 57}, {7, 6, 57}, {8, 7, 57}, {1, 8, 57}, {49, 50, 58},
{50, 51, 58}, {51, 52, 58}, {52, 53, 58}, {53, 54, 58}, {54, 55, 58},
{55, 56, 58}, {56, 49, 58}};
auto triMesh = new btTriangleMesh();
for (auto i = 0u; i < 112; ++i) {
btVector3 vertices[3];
const auto& index0 = f[i][0];
const auto& index1 = f[i][1];
const auto& index2 = f[i][2];
const auto& p0 = v[index0];
const auto& p1 = v[index1];
const auto& p2 = v[index2];
vertices[0] = btVector3(p0[0] * sizeX, p0[1] * sizeY, p0[2] * sizeZ);
vertices[1] = btVector3(p1[0] * sizeX, p1[1] * sizeY, p1[2] * sizeZ);
vertices[2] = btVector3(p2[0] * sizeX, p2[1] * sizeY, p2[2] * sizeZ);
triMesh->addTriangle(vertices[0], vertices[1], vertices[2]);
}
auto gimpactMeshShape = std::make_unique<btGImpactMeshShape>(triMesh);
gimpactMeshShape->updateBound();
return gimpactMeshShape;
}
//==============================================================================
std::unique_ptr<btCollisionShape> createBulletCollisionShapeFromAssimpScene(
const Eigen::Vector3d& scale, const aiScene* scene)
{
auto triMesh = new btTriangleMesh();
for (auto i = 0u; i < scene->mNumMeshes; ++i) {
for (auto j = 0u; j < scene->mMeshes[i]->mNumFaces; ++j) {
btVector3 vertices[3];
for (auto k = 0u; k < 3; ++k) {
const aiVector3D& vertex
= scene->mMeshes[i]
->mVertices[scene->mMeshes[i]->mFaces[j].mIndices[k]];
vertices[k] = btVector3(
vertex.x * scale[0], vertex.y * scale[1], vertex.z * scale[2]);
}
triMesh->addTriangle(vertices[0], vertices[1], vertices[2]);
}
}
const bool makeConvexMesh
= scene->mNumMeshes == 1 && isConvex(scene->mMeshes[0]);
if (makeConvexMesh) {
auto convexMeshShape = std::make_unique<btConvexTriangleMeshShape>(triMesh);
convexMeshShape->setMargin(0.0f);
convexMeshShape->setUserPointer(triMesh);
return convexMeshShape;
} else {
auto gimpactMeshShape = std::make_unique<btGImpactMeshShape>(triMesh);
gimpactMeshShape->updateBound();
gimpactMeshShape->setUserPointer(triMesh);
return gimpactMeshShape;
}
}
//==============================================================================
std::unique_ptr<btCollisionShape> createBulletCollisionShapeFromAssimpMesh(
const aiMesh* mesh)
{
auto triMesh = new btTriangleMesh();
for (auto i = 0u; i < mesh->mNumFaces; ++i) {
btVector3 vertices[3];
for (auto j = 0u; j < 3; ++j) {
const aiVector3D& vertex = mesh->mVertices[mesh->mFaces[i].mIndices[j]];
vertices[j] = btVector3(vertex.x, vertex.y, vertex.z);
}
triMesh->addTriangle(vertices[0], vertices[1], vertices[2]);
}
const bool makeConvexMesh = isConvex(mesh);
if (makeConvexMesh) {
auto convexMeshShape = std::make_unique<btConvexTriangleMeshShape>(triMesh);
convexMeshShape->setMargin(0.0f);
return convexMeshShape;
} else {
auto gimpactMeshShape = std::make_unique<btGImpactMeshShape>(triMesh);
gimpactMeshShape->updateBound();
return gimpactMeshShape;
}
}
//==============================================================================
template <typename HeightmapShapeT>
std::unique_ptr<BulletCollisionShape> createBulletCollisionShapeFromHeightmap(
const HeightmapShapeT* heightMap)
{
// get the heightmap parameters
const auto& scale = heightMap->getScale();
const auto minHeight = heightMap->getMinHeight();
const auto maxHeight = heightMap->getMaxHeight();
// determine which data type (float or double) is to be used for the field
PHY_ScalarType scalarType = PHY_FLOAT;
if (std::is_same<typename HeightmapShapeT::S, double>::value) {
dterr << "Bullet does not support DOUBLE as heightmap field yet.\n";
return nullptr;
// take this back in as soon as it is supported
// scalarType = PHY_DOUBLE;
}
// the y-values in the height field need to be flipped
heightMap->flipY();
const auto& heights = heightMap->getHeightField();
// create the height field
const btVector3 localScaling(scale.x(), scale.y(), scale.z());
const bool flipQuadEdges = false;
auto heightFieldShape = std::make_unique<btHeightfieldTerrainShape>(
heightMap->getWidth(), // Width of height field
heightMap->getDepth(), // Depth of height field
heights.data(), // Height values
1, // Height scaling
minHeight, // Min height
maxHeight, // Max height
2, // Up axis
scalarType, // Float or double field
flipQuadEdges); // Flip quad edges
heightFieldShape->setLocalScaling(localScaling);
heightFieldShape->setUseZigzagSubdivision(true);
// change the relative transform of the height field so that the minimum
// height is at the same z coordinate. Bullet shifts the height map such
// that its center is the AABB center.
const btVector3 trans(
0, 0, ((maxHeight - minHeight) * 0.5 + minHeight) * scale.z());
btTransform relativeShapeTransform(btMatrix3x3::getIdentity(), trans);
// bullet places the heightfield such that the origin is in the
// middle of the AABB. We want however that the minimum height value
// is on x/y plane.
btVector3 min;
btVector3 max;
heightFieldShape->getAabb(btTransform::getIdentity(), min, max);
dtdbg << "DART Bullet heightfield AABB: min = {" << min.x() << ", " << min.y()
<< ", " << min.z() << "}, max = {" << max.x() << ", " << max.y() << ", "
<< max.z() << "}"
<< " (will be translated by z=" << trans.z() << ")" << std::endl;
return std::make_unique<BulletCollisionShape>(
std::move(heightFieldShape), relativeShapeTransform);
}