-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
proximity_engine_test.cc
4730 lines (4258 loc) · 199 KB
/
proximity_engine_test.cc
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
#include "drake/geometry/proximity_engine.h"
#include <cmath>
#include <filesystem>
#include <fstream>
#include <unordered_map>
#include <utility>
#include <vector>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/ostream.h>
#include <gtest/gtest.h>
#include "drake/common/find_resource.h"
#include "drake/common/temp_directory.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_no_throw.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/geometry/proximity/deformable_contact_internal.h"
#include "drake/geometry/proximity/hydroelastic_callback.h"
#include "drake/geometry/proximity/make_sphere_mesh.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/geometry/shape_specification.h"
#include "drake/math/autodiff.h"
#include "drake/math/autodiff_gradient.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/rotation_matrix.h"
namespace drake {
namespace geometry {
namespace internal {
// Compare witness pair. Note that we can switch body A with body B in one pair,
// and the comparison result would be the same.
template <typename T>
void CompareSignedDistancePair(const SignedDistancePair<T>& pair,
const SignedDistancePair<T>& pair_expected,
double tol) {
using std::abs;
EXPECT_TRUE(abs(pair.distance - pair_expected.distance) < tol);
ASSERT_LT(pair.id_A, pair_expected.id_B);
EXPECT_EQ(pair.id_B, pair_expected.id_B);
EXPECT_TRUE(CompareMatrices(pair.p_ACa, pair_expected.p_ACa, tol,
MatrixCompareType::absolute));
EXPECT_TRUE(CompareMatrices(pair.p_BCb, pair_expected.p_BCb, tol,
MatrixCompareType::absolute));
}
class ProximityEngineTester {
public:
ProximityEngineTester() = delete;
template <typename T>
static bool IsDeepCopy(const ProximityEngine<T>& test_engine,
const ProximityEngine<T>& ref_engine) {
return ref_engine.IsDeepCopy(test_engine);
}
template <typename T>
static math::RigidTransformd GetX_WG(GeometryId id, bool is_dynamic,
const ProximityEngine<T>& engine) {
return engine.GetX_WG(id, is_dynamic);
}
template <typename T>
static HydroelasticType hydroelastic_type(
GeometryId id, const ProximityEngine<T>& engine) {
return engine.hydroelastic_geometries().hydroelastic_type(id);
}
template <typename T>
static bool IsFclConvexType(const ProximityEngine<T>& engine,
GeometryId id) {
return engine.IsFclConvexType(id);
}
template <typename T>
static const internal::deformable::Geometries&
get_deformable_contact_geometries(const ProximityEngine<T>& engine) {
return engine.deformable_contact_geometries();
}
};
namespace deformable {
class GeometriesTester {
public:
GeometriesTester() = delete;
static const DeformableGeometry& get_deformable_geometry(
const Geometries& geometries, GeometryId id) {
return geometries.deformable_geometries_.at(id);
}
static const RigidGeometry& get_rigid_geometry(const Geometries& geometries,
GeometryId id) {
return geometries.rigid_geometries_.at(id);
}
};
} // namespace deformable
namespace {
constexpr double kInf = std::numeric_limits<double>::infinity();
using math::RigidTransform;
using math::RigidTransformd;
using math::RollPitchYawd;
using math::RotationMatrixd;
using Eigen::AngleAxisd;
using Eigen::Translation3d;
using Eigen::Vector2d;
using Eigen::Vector3d;
using std::make_shared;
using std::make_unique;
using std::shared_ptr;
using std::unordered_map;
using std::vector;
using symbolic::Expression;
// Tests for manipulating the population of the proximity engine.
// Test simple addition of dynamic geometry.
GTEST_TEST(ProximityEngineTests, AddDynamicGeometry) {
ProximityEngine<double> engine;
Sphere sphere{0.5};
const GeometryId id = GeometryId::get_new_id();
engine.AddDynamicGeometry(sphere, {}, id);
EXPECT_EQ(engine.num_geometries(), 1);
EXPECT_EQ(engine.num_anchored(), 0);
EXPECT_EQ(engine.num_dynamic(), 1);
}
// "Processing" hydroelastic geometry is simply a case of invoking a method
// on hydroelastic::Geometries. All error handling is done there. So, it is
// sufficient to confirm that it is being properly invoked. We'll simply attempt
// to instantiate every shape and assert its classification based on whether
// it's supported or not (note: this test doesn't depend on the choice of
// rigid/compliant -- for each shape, we pick an arbitrary compliance type,
// preferring one that is supported over one that is not. Otherwise, the
// compliance choice is immaterial.) One exception is that the rigid Mesh and
// the compliant Mesh use two different kinds of files, so we test both of them.
GTEST_TEST(ProximityEngineTests, ProcessHydroelasticProperties) {
ProximityEngine<double> engine;
// All of the geometries will have a scale comparable to edge_length, so that
// the mesh creation is as cheap as possible. The exception is Mesh
// geometry since we have no re-meshing.
const double edge_length = 0.5;
const double E = 1e8; // Elastic modulus.
ProximityProperties soft_properties;
AddCompliantHydroelasticProperties(edge_length, E, &soft_properties);
ProximityProperties rigid_properties;
AddRigidHydroelasticProperties(edge_length, &rigid_properties);
// Case: compliant sphere.
{
Sphere sphere{edge_length};
const GeometryId sphere_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(sphere, {}, sphere_id, soft_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(sphere_id, engine),
HydroelasticType::kSoft);
}
// Case: rigid cylinder.
{
Cylinder cylinder{edge_length, edge_length};
const GeometryId cylinder_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(cylinder, {}, cylinder_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(cylinder_id, engine),
HydroelasticType::kRigid);
}
// Case: rigid ellipsoid.
{
Ellipsoid ellipsoid{edge_length, edge_length, edge_length};
const GeometryId ellipsoid_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(ellipsoid, {}, ellipsoid_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(ellipsoid_id, engine),
HydroelasticType::kRigid);
}
// Case: rigid capsule.
{
Capsule capsule{edge_length, edge_length};
const GeometryId capsule_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(capsule, {}, capsule_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(capsule_id, engine),
HydroelasticType::kRigid);
}
// Case: rigid half_space.
{
HalfSpace half_space;
const GeometryId half_space_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(half_space, {}, half_space_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(half_space_id, engine),
HydroelasticType::kRigid);
}
// Case: rigid box.
{
Box box{edge_length, edge_length, edge_length};
const GeometryId box_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(box, {}, box_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(box_id, engine),
HydroelasticType::kRigid);
}
// Case: rigid mesh.
{
Mesh mesh{
drake::FindResourceOrThrow("drake/geometry/test/non_convex_mesh.obj"),
1.0 /* scale */};
const GeometryId mesh_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(mesh, {}, mesh_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(mesh_id, engine),
HydroelasticType::kRigid);
}
// Case: compliant mesh.
{
Mesh mesh{
drake::FindResourceOrThrow("drake/geometry/test/non_convex_mesh.vtk"),
1.0 /* scale */};
const GeometryId mesh_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(mesh, {}, mesh_id, soft_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(mesh_id, engine),
HydroelasticType::kSoft);
}
// Case: rigid convex.
{
Convex convex{
drake::FindResourceOrThrow("drake/geometry/test/quad_cube.obj"),
edge_length};
const GeometryId convex_id = GeometryId::get_new_id();
engine.AddDynamicGeometry(convex, {}, convex_id, rigid_properties);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(convex_id, engine),
HydroelasticType::kRigid);
}
}
// Adds a single shape to the given engine with the indicated anchored/dynamic
// configuration and compliant type.
std::pair<GeometryId, RigidTransformd> AddShape(ProximityEngine<double>* engine,
const Shape& shape,
bool is_anchored, bool is_soft,
const Vector3d& p_S1S2_W) {
RigidTransformd X_WS = RigidTransformd(p_S1S2_W);
const GeometryId id_S = GeometryId::get_new_id();
// We'll mindlessly provide edge_length; even if the shape doesn't require
// it.
const double edge_length = 0.5;
ProximityProperties properties;
if (is_soft) {
AddCompliantHydroelasticProperties(edge_length, 1e8, &properties);
} else {
AddRigidHydroelasticProperties(edge_length, &properties);
}
if (is_anchored) {
engine->AddAnchoredGeometry(shape, X_WS, id_S, properties);
} else {
engine->AddDynamicGeometry(shape, X_WS, id_S, properties);
}
return std::make_pair(id_S, X_WS);
}
unordered_map<GeometryId, RigidTransformd> PopulateEngine(
ProximityEngine<double>* engine, const Shape& shape1, bool anchored1,
bool soft1, const Shape& shape2, bool anchored2, bool soft2,
const Vector3d& p_S1S2_W = Vector3d(0, 0, 0)) {
unordered_map<GeometryId, RigidTransformd> X_WGs;
RigidTransformd X_WG;
GeometryId id1, id2;
std::tie(id1, X_WG) =
AddShape(engine, shape1, anchored1, soft1, Vector3d::Zero());
X_WGs.insert({id1, X_WG});
std::tie(id2, X_WG) = AddShape(engine, shape2, anchored2, soft2, p_S1S2_W);
X_WGs.insert({id2, X_WG});
engine->UpdateWorldPoses(X_WGs);
return X_WGs;
}
// The autodiff support is independent of what the contact surface mesh
// representation is; so we'll simply use kTriangle.
GTEST_TEST(ProximityEngineTest, ComputeContactSurfacesAutodiffSupport) {
const bool anchored{true};
const bool soft{true};
const Sphere sphere{0.2};
const Mesh mesh{
drake::FindResourceOrThrow("drake/geometry/test/non_convex_mesh.obj"),
1.0 /* scale */};
// Case: Compliant sphere and rigid mesh with AutoDiffXd -- confirm the
// contact surface has derivatives.
{
ProximityEngine<double> engine_d;
const auto X_WGs_d = PopulateEngine(&engine_d, sphere, anchored, soft, mesh,
!anchored, !soft);
const auto engine_ad = engine_d.ToScalarType<AutoDiffXd>();
unordered_map<GeometryId, RigidTransform<AutoDiffXd>> X_WGs_ad;
bool added_derivatives = false;
for (const auto& [id, X_WG_d] : X_WGs_d) {
if (!added_derivatives) {
// We'll set the derivatives on p_WGo for the first geometry; all others
// we'll pass through.
const Vector3<AutoDiffXd> p_WGo =
math::InitializeAutoDiff(X_WG_d.translation());
X_WGs_ad[id] = RigidTransform<AutoDiffXd>(
X_WG_d.rotation().cast<AutoDiffXd>(), p_WGo);
added_derivatives = true;
} else {
X_WGs_ad[id] = RigidTransform<AutoDiffXd>(X_WG_d.GetAsMatrix34());
}
}
std::vector<ContactSurface<AutoDiffXd>> surfaces;
std::vector<PenetrationAsPointPair<AutoDiffXd>> point_pairs;
// We assume that ComputeContactSurfacesWithFallback() exercises the same
// code as ComputeContactSurfaces(); they both pass through the hydroelastic
// callback. So, exercising one is "sufficient". If they ever deviate in
// execution (i.e., there were to no longer share the same callback), this
// test would have to be elaborated.
engine_ad->ComputeContactSurfacesWithFallback(
HydroelasticContactRepresentation::kTriangle, X_WGs_ad, &surfaces,
&point_pairs);
EXPECT_EQ(surfaces.size(), 1);
EXPECT_EQ(point_pairs.size(), 0);
// We'll poke *one* quantity of the surface mesh to confirm it has
// derivatives. We won't consider the *value*, just the existence as proof
// that it has been wired up to code that has already tested value.
EXPECT_EQ(surfaces[0].tri_mesh_W().vertex(0).x().derivatives().size(), 3);
}
// Case: Rigid sphere and mesh with AutoDiffXd -- contact would be a point
// pair.
{
ProximityEngine<double> engine_d;
const auto X_WGs_d =
PopulateEngine(&engine_d, sphere, false, !soft, sphere, false, !soft);
const auto engine_ad = engine_d.ToScalarType<AutoDiffXd>();
unordered_map<GeometryId, RigidTransform<AutoDiffXd>> X_WGs_ad;
for (const auto& [id, X_WG_d] : X_WGs_d) {
X_WGs_ad[id] = RigidTransform<AutoDiffXd>(X_WG_d.GetAsMatrix34());
}
std::vector<ContactSurface<AutoDiffXd>> surfaces;
std::vector<PenetrationAsPointPair<AutoDiffXd>> point_pairs;
engine_ad->ComputeContactSurfacesWithFallback(
HydroelasticContactRepresentation::kTriangle, X_WGs_ad, &surfaces,
&point_pairs);
EXPECT_EQ(surfaces.size(), 0);
EXPECT_EQ(point_pairs.size(), 1);
}
}
// Meshes are treated specially in proximity engine. Proximity queries on
// non-convex meshes are not yet supported. A Mesh specification is treated
// implicitly as the convex hull of the mesh. This is implemented by
// instantiating an "invalid" fcl::Convex (see
// ProximityEngine::Impl::ImplementGeometry(Mesh) for details). For test
// purposes, we'll confirm that the associated fcl object *is* a Convex
// shape. Furthermore, we'll use a regression test to confirm the expected
// behavior, to wit:
//
// - A concave mesh queries penetration and distance like its convex hull.
// - A concave mesh queries hydroelastic based on the actual mesh.
//
// The test doesn't depend on the mesh representation type.
GTEST_TEST(ProximityEngineTests, MeshSupportAsConvex) {
/* This mesh looks like this:
+z
-2 -1 ┆ +1 +2
+0.5 ┈┈┈┏━━━━━━┓┉┉┉┉┉┼┉┉┉┉┉┏━━━━━━┓
┃░░░░░░┃▒▒▒▒▒┆▒▒▒▒▒┃░░░░░░┃
┄┄┄┄┄┄┄╂┄┄┄┄┄┄╂┄┄┄┄┄┼┄┄┄┄┄╂┄┄┄┄┄┄╂┄┄┄┄┄┄ +x
┃░░░░░░┃▒▒▒▒▒┆▒▒▒▒▒┃░░░░░░┃
-0.5 ┈┈┃░░░░░░┗━━━━━P━━━━━┛░░░░░░┃ ━━ - Surface of concave geometry.
┃░░░░░░░░░░░░┆░░░░░░░░░░░░┃ ░░ - Interior of concave geometry.
┃░░░░░░░░░░░░┆░░░░░░░░░░░░┃ ▒▒ - Inside convex hull, outside
┃░░░░░░░░░░░░┆░░░░░░░░░░░░┃ concave geometry.
-2 ┈┈┈┗━━━━━━━━━━━━┿━━━━━━━━━━━━┛
┆
- We'll place a sphere at the origin with radius R.
- The nearest point to the sphere on the *concave* geometry is shown as
point P. Its distance is 0.5 - R.
- The signed distance to the *convex region* will be -(0.5 + R).
- If R < 0.5, there is *no* hydroelastic contact surface.
- if R > 0.5, there will be one.
*/
/* Because we're using the general convexity algorithm for distance and
penetration, we'll lose a great deal of precision in the answer. Empirically,
for this test case, even sqrt(eps) was insufficient. This value appears to
be sufficient. In some cases, an eps as small as 2e-7 was sufficient. But
for the most inaccurate test (slightly seaprated with large sphere), the
error was as larage as 2e-5. */
constexpr double kEps = 2e-5;
for (double radius : {0.25, 0.75}) {
ProximityEngine<double> engine;
// The actual non-convex mesh. Used in all queries.
const Mesh mesh{
drake::FindResourceOrThrow("drake/geometry/test/extruded_u.obj"),
1.0 /* scale */};
const auto& [mesh_id, X_WM] =
AddShape(&engine, mesh, true /* is_anchored */, false /* is_soft */,
Vector3d::Zero());
ASSERT_TRUE(ProximityEngineTester::IsFclConvexType(engine, mesh_id));
const auto& [sphere_id, X_MS] =
AddShape(&engine, Sphere(radius), false /* is_anchored */,
true /* is soft */, Vector3d::Zero());
unordered_map<GeometryId, RigidTransformd> X_WGs{{mesh_id, X_WM},
{sphere_id, X_WM * X_MS}};
engine.UpdateWorldPoses(X_WGs);
// Existence of a contact surface depends on the radius of the sphere.
const auto contact_surfaces = engine.ComputeContactSurfaces(
HydroelasticContactRepresentation::kTriangle, X_WGs);
EXPECT_EQ(contact_surfaces.size(), radius > 0.5 ? 1 : 0);
{
// Perform the queries with the sphere at the origin; it lies inside the
// convex hull giving negative signed distance and non-zero penetration
// depth.
const auto signed_distance_pairs =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kInf);
ASSERT_EQ(signed_distance_pairs.size(), 1);
EXPECT_NEAR(signed_distance_pairs[0].distance, -(0.5 + radius), kEps);
const auto point_pairs = engine.ComputePointPairPenetration(X_WGs);
ASSERT_EQ(1, point_pairs.size());
EXPECT_NEAR(point_pairs[0].depth, 0.5 + radius, kEps);
const auto candidates = engine.FindCollisionCandidates();
ASSERT_EQ(1, candidates.size());
EXPECT_TRUE(engine.HasCollisions());
}
{
// Move the sphere slightly outside the convex hull. We should get
// slightly positive signed distance and no penetration.
constexpr double kDistance = 1e-3;
X_WGs[sphere_id] =
RigidTransformd(Vector3d(0, 0, 0.5 + radius + kDistance));
engine.UpdateWorldPoses(X_WGs);
const auto signed_distance_pairs =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kInf);
ASSERT_EQ(signed_distance_pairs.size(), 1);
EXPECT_NEAR(signed_distance_pairs[0].distance, kDistance, kEps);
const auto point_pairs = engine.ComputePointPairPenetration(X_WGs);
ASSERT_EQ(0, point_pairs.size());
const auto candidates = engine.FindCollisionCandidates();
ASSERT_EQ(0, candidates.size());
EXPECT_FALSE(engine.HasCollisions());
}
}
}
// Tests that passing VTK file in Mesh for Point contact will throw.
GTEST_TEST(ProximityEngineTests, VtkForPointContactThrow) {
ProximityEngine<double> engine;
const Mesh vtk_mesh{
drake::FindResourceOrThrow("drake/geometry/test/non_convex_mesh.vtk")};
DRAKE_EXPECT_THROWS_MESSAGE(
engine.AddAnchoredGeometry(vtk_mesh, RigidTransformd::Identity(),
GeometryId::get_new_id()),
".*only support .obj files.*");
}
// Tests simple addition of anchored geometry.
GTEST_TEST(ProximityEngineTests, AddAnchoredGeometry) {
ProximityEngine<double> engine;
const Sphere sphere{0.5};
const RigidTransformd X_WG{Vector3d{1, 2, 3}};
const GeometryId id = GeometryId::get_new_id();
engine.AddAnchoredGeometry(sphere, X_WG, id);
EXPECT_EQ(engine.num_geometries(), 1);
EXPECT_EQ(engine.num_anchored(), 1);
EXPECT_EQ(engine.num_dynamic(), 0);
EXPECT_TRUE(CompareMatrices(
ProximityEngineTester::GetX_WG(id, false, engine).GetAsMatrix34(),
X_WG.GetAsMatrix34()));
}
// Tests addition of both dynamic and anchored geometry.
GTEST_TEST(ProximityEngineTests, AddMixedGeometry) {
ProximityEngine<double> engine;
const Sphere sphere{0.5};
const RigidTransformd X_WA{Vector3d{1, 2, 3}};
const GeometryId id_1 = GeometryId::get_new_id();
engine.AddAnchoredGeometry(sphere, X_WA, id_1);
EXPECT_TRUE(CompareMatrices(
ProximityEngineTester::GetX_WG(id_1, false, engine).GetAsMatrix34(),
X_WA.GetAsMatrix34()));
const RigidTransformd X_WD{Vector3d{-1, -2, -3}};
const GeometryId id_2 = GeometryId::get_new_id();
engine.AddDynamicGeometry(sphere, X_WD, id_2);
EXPECT_EQ(engine.num_geometries(), 2);
EXPECT_EQ(engine.num_anchored(), 1);
EXPECT_EQ(engine.num_dynamic(), 1);
EXPECT_TRUE(CompareMatrices(
ProximityEngineTester::GetX_WG(id_2, true, engine).GetAsMatrix34(),
X_WD.GetAsMatrix34()));
}
// Tests replacing the proximity properties for a given geometry.
GTEST_TEST(ProximityEngineTests, ReplaceProperties) {
// Some quick aliases to make the tests more compact.
using PET = ProximityEngineTester;
const HydroelasticType kUndefined = HydroelasticType::kUndefined;
const HydroelasticType kRigid = HydroelasticType::kRigid;
ProximityEngine<double> engine;
const double radius = 0.5;
InternalGeometry sphere(SourceId::get_new_id(), make_unique<Sphere>(radius),
FrameId::get_new_id(), GeometryId::get_new_id(),
"sphere", RigidTransformd());
// Note: The order of these tests matter; one builds on the next. Re-ordering
// *may* break the test.
// Case: throws when the id doesn't refer to a valid geometry.
DRAKE_EXPECT_THROWS_MESSAGE(
engine.UpdateRepresentationForNewProperties(sphere, {}),
"The proximity engine does not contain a geometry with the id \\d+; its "
"properties cannot be updated");
// Case: The new and old properties have no hydroelastic declarations, however
// it mindlessly attempts to update the hydroelastic representation.
{
ProximityProperties props;
props.AddProperty("foo", "bar", 1.0);
engine.AddDynamicGeometry(sphere.shape(), {}, sphere.id(), props);
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kUndefined);
DRAKE_EXPECT_NO_THROW(
engine.UpdateRepresentationForNewProperties(sphere, {}));
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kUndefined);
}
// Case: The new set has hydroelastic properties, the old does not; change
// required.
{
ProximityProperties props;
// Pick a characteristic length sufficiently large that we create the
// coarsest, cheapest mesh possible.
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kUndefined);
props.AddProperty(kHydroGroup, kElastic,
std::numeric_limits<double>::infinity());
AddRigidHydroelasticProperties(3 * radius, &props);
DRAKE_EXPECT_NO_THROW(
engine.UpdateRepresentationForNewProperties(sphere, props));
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kRigid);
}
// Case: The new set does *not* have hydroelastic properties, the old does;
// this should remove the hydroelastic representation.
{
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kRigid);
DRAKE_EXPECT_NO_THROW(engine.UpdateRepresentationForNewProperties(
sphere, ProximityProperties()));
EXPECT_EQ(PET::hydroelastic_type(sphere.id(), engine), kUndefined);
}
// Create a baseline property set that requests a compliant hydroelastic
// representation, but is not necessarily sufficient to define one.
ProximityProperties hydro_trigger;
hydro_trigger.AddProperty(kHydroGroup, kComplianceType,
HydroelasticType::kSoft);
// Case: New properties request hydroelastic, but they are incomplete and
// efforts to assign those properties throw.
{
ProximityProperties bad_props_no_elasticity(hydro_trigger);
bad_props_no_elasticity.AddProperty(kHydroGroup, kRezHint, 1.25);
DRAKE_EXPECT_THROWS_MESSAGE(
engine.UpdateRepresentationForNewProperties(sphere,
bad_props_no_elasticity),
"Cannot create soft Sphere; missing the .+ property");
ProximityProperties bad_props_no_length(hydro_trigger);
bad_props_no_length.AddProperty(kHydroGroup, kElastic, 5e8);
DRAKE_EXPECT_THROWS_MESSAGE(
engine.UpdateRepresentationForNewProperties(sphere,
bad_props_no_length),
"Cannot create soft Sphere; missing the .+ property");
}
}
// Removes geometry (dynamic and anchored) from the engine. The test creates
// a _unique_ engine instance with all dynamic or all anchored geometries.
// It is not necessary to create a mixed engine because the two geometry
// types are segregated.
GTEST_TEST(ProximityEngineTests, RemoveGeometry) {
for (bool is_dynamic : {true, false}) {
ProximityEngine<double> engine;
// Removing a geometry that doesn't exist, throws.
EXPECT_THROW(engine.RemoveGeometry(GeometryId::get_new_id(), true),
std::logic_error);
// Populate the world with three anchored spheres located on the x-axis at
// x = 0, 2, & 4. With radius of 0.5, they should *not* be colliding.
Sphere sphere{0.5};
std::vector<GeometryId> ids;
std::unordered_map<GeometryId, RigidTransformd> poses;
for (int i = 0; i < 3; ++i) {
const GeometryId id = GeometryId::get_new_id();
ids.push_back(id);
poses.insert({id, RigidTransformd{Translation3d{i * 2.0, 0, 0}}});
// Add rigid properties so we can confirm removal of hydroelastic
// representation. We use rigid here to make sure things get invoked and
// rely on the implementation of hydroelastic::Geometries to distinguish
// soft and rigid.
ProximityProperties props;
AddRigidHydroelasticProperties(1.0, &props);
if (is_dynamic) {
engine.AddDynamicGeometry(sphere, poses[id], id, props);
} else {
engine.AddAnchoredGeometry(sphere, poses[id], id, props);
}
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(id, engine),
HydroelasticType::kRigid);
}
int expected_count = static_cast<int>(engine.num_geometries());
EXPECT_EQ(engine.num_geometries(), expected_count);
EXPECT_EQ(engine.num_anchored(), is_dynamic ? 0 : expected_count);
EXPECT_EQ(engine.num_dynamic(), is_dynamic ? expected_count : 0);
engine.UpdateWorldPoses(poses);
// Remove objects out of order from how they were added. Confirms that the
// globals are consistent and that the geometry can only be removed once.
for (int index : {1, 2, 0}) {
--expected_count;
const GeometryId remove_id = ids[index];
engine.RemoveGeometry(remove_id, is_dynamic);
EXPECT_EQ(engine.num_geometries(), expected_count);
EXPECT_EQ(engine.num_anchored(), is_dynamic ? 0 : expected_count);
EXPECT_EQ(engine.num_dynamic(), is_dynamic ? expected_count : 0);
EXPECT_THROW(engine.RemoveGeometry(remove_id, is_dynamic),
std::logic_error);
EXPECT_EQ(ProximityEngineTester::hydroelastic_type(remove_id, engine),
HydroelasticType::kUndefined);
}
}
}
// Tests for reading .obj files.------------------------------------------------
// Tests exception when we fail to read an .obj file into a Convex.
GTEST_TEST(ProximityEngineTests, FailedParsing) {
ProximityEngine<double> engine;
// The obj contains multiple objects.
{
Convex convex{drake::FindResourceOrThrow(
"drake/geometry/test/forbidden_two_cubes.obj"),
1.0};
DRAKE_EXPECT_THROWS_MESSAGE(
engine.AddDynamicGeometry(convex, {}, GeometryId::get_new_id()),
".*only OBJs with a single object.*");
}
const std::filesystem::path temp_dir = temp_directory();
// An empty file.
{
const std::filesystem::path file = temp_dir / "empty.obj";
std::ofstream f(file.string());
f.close();
Convex convex{file.string(), 1.0};
DRAKE_EXPECT_THROWS_MESSAGE(
engine.AddDynamicGeometry(convex, {}, GeometryId::get_new_id()),
"The file parsed contains no objects;.+");
}
// The file does not have OBJ contents..
{ const std::filesystem::path file = temp_dir / "not_really_an_obj.obj";
std::ofstream f(file.string());
f << "I'm not a valid obj\n";
f.close();
Convex convex{file.string(), 1.0};
DRAKE_EXPECT_THROWS_MESSAGE(
engine.AddDynamicGeometry(convex, {}, GeometryId::get_new_id()),
"The file parsed contains no objects;.+");}
}
// Tests for copy/move semantics. ---------------------------------------------
// Tests the copy semantics of the ProximityEngine -- the copy is a complete,
// deep copy. Every type of shape specification must be included in this test.
GTEST_TEST(ProximityEngineTests, CopySemantics) {
ProximityEngine<double> ref_engine;
Sphere sphere{0.5};
RigidTransformd pose = RigidTransformd::Identity();
// NOTE: The GeometryId values are all lies; the values are arbitrary but
// do not matter in the context of this test.
ref_engine.AddAnchoredGeometry(sphere, pose, GeometryId::get_new_id());
ref_engine.AddDynamicGeometry(sphere, pose, GeometryId::get_new_id());
Cylinder cylinder{0.1, 1.0};
ref_engine.AddDynamicGeometry(cylinder, pose, GeometryId::get_new_id());
Box box{0.1, 0.2, 0.3};
ref_engine.AddDynamicGeometry(box, pose, GeometryId::get_new_id());
Capsule capsule{0.1, 1.0};
ref_engine.AddDynamicGeometry(capsule, pose, GeometryId::get_new_id());
Ellipsoid ellipsoid{0.1, 0.2, 0.3};
ref_engine.AddDynamicGeometry(ellipsoid, pose, GeometryId::get_new_id());
HalfSpace half_space{};
ref_engine.AddDynamicGeometry(half_space, pose, GeometryId::get_new_id());
Convex convex{drake::FindResourceOrThrow("drake/geometry/test/quad_cube.obj"),
1.0};
ref_engine.AddDynamicGeometry(convex, pose, GeometryId::get_new_id());
ProximityEngine<double> copy_construct(ref_engine);
ProximityEngineTester::IsDeepCopy(copy_construct, ref_engine);
ProximityEngine<double> copy_assign;
copy_assign = ref_engine;
ProximityEngineTester::IsDeepCopy(copy_assign, ref_engine);
}
// Tests the move semantics of the ProximityEngine -- the source is restored to
// default state.
GTEST_TEST(ProximityEngineTests, MoveSemantics) {
ProximityEngine<double> engine;
Sphere sphere{0.5};
RigidTransformd pose = RigidTransformd::Identity();
engine.AddAnchoredGeometry(sphere, pose, GeometryId::get_new_id());
engine.AddDynamicGeometry(sphere, pose, GeometryId::get_new_id());
ProximityEngine<double> move_construct(std::move(engine));
EXPECT_EQ(move_construct.num_geometries(), 2);
EXPECT_EQ(move_construct.num_anchored(), 1);
EXPECT_EQ(move_construct.num_dynamic(), 1);
EXPECT_EQ(engine.num_geometries(), 0);
EXPECT_EQ(engine.num_anchored(), 0);
EXPECT_EQ(engine.num_dynamic(), 0);
ProximityEngine<double> move_assign;
move_assign = std::move(move_construct);
EXPECT_EQ(move_assign.num_geometries(), 2);
EXPECT_EQ(move_assign.num_anchored(), 1);
EXPECT_EQ(move_assign.num_dynamic(), 1);
EXPECT_EQ(move_construct.num_geometries(), 0);
EXPECT_EQ(move_construct.num_anchored(), 0);
EXPECT_EQ(move_construct.num_dynamic(), 0);
}
// Signed distance tests -- testing data flow; not testing the value of the
// query.
// A scene with no geometry reports no witness pairs.
GTEST_TEST(ProximityEngineTests, SignedDistanceClosestPointsOnEmptyScene) {
ProximityEngine<double> engine;
const unordered_map<GeometryId, RigidTransformd> X_WGs;
const auto results =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kInf);
EXPECT_EQ(results.size(), 0);
}
// A scene with a single anchored geometry reports no distance.
GTEST_TEST(ProximityEngineTests, SignedDistanceClosestPointsSingleAnchored) {
ProximityEngine<double> engine;
Sphere sphere{0.5};
const GeometryId id = GeometryId::get_new_id();
const unordered_map<GeometryId, RigidTransformd> X_WGs{
{id, RigidTransformd::Identity()}};
engine.AddAnchoredGeometry(sphere, X_WGs.at(id), id);
const auto results =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kInf);
EXPECT_EQ(results.size(), 0);
}
// Tests that anchored geometry don't report closest distance with each other.
GTEST_TEST(ProximityEngineTests, SignedDistanceClosestPointsMultipleAnchored) {
ProximityEngine<double> engine;
unordered_map<GeometryId, RigidTransformd> X_WGs;
const double radius = 0.5;
Sphere sphere{radius};
const GeometryId id_A = GeometryId::get_new_id();
X_WGs[id_A] = RigidTransformd::Identity();
engine.AddAnchoredGeometry(sphere, X_WGs.at(id_A), id_A);
const GeometryId id_B = GeometryId::get_new_id();
X_WGs[id_B] = RigidTransformd{Translation3d{1.8 * radius, 0, 0}};
engine.AddAnchoredGeometry(sphere, X_WGs.at(id_B), id_B);
const auto results =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kInf);
EXPECT_EQ(results.size(), 0);
}
// Tests that the maximum distance value is respected. Confirms that two shapes
// are included/excluded based on a distance just inside and outside that
// maximum distance, respectively.
GTEST_TEST(ProximityEngineTests, SignedDistanceClosestPointsMaxDistance) {
ProximityEngine<double> engine;
const GeometryId id_A = GeometryId::get_new_id();
const GeometryId id_B = GeometryId::get_new_id();
unordered_map<GeometryId, RigidTransformd> X_WGs{
{id_A, RigidTransformd::Identity()}, {id_B, RigidTransformd::Identity()}};
const double radius = 0.5;
Sphere sphere{radius};
engine.AddDynamicGeometry(sphere, {}, id_A);
engine.AddDynamicGeometry(sphere, {}, id_B);
const double kMaxDistance = 1.0;
const double kEps = 2 * std::numeric_limits<double>::epsilon();
const double kCenterDistance = kMaxDistance + radius + radius;
// Case: Just inside the maximum distance.
{
const Vector3d p_WB =
Vector3d(2, 3, 4).normalized() * (kCenterDistance - kEps);
X_WGs[id_B].set_translation(p_WB);
engine.UpdateWorldPoses(X_WGs);
const auto results =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kMaxDistance);
EXPECT_EQ(results.size(), 1);
}
// Case: Just outside the maximum distance.
{
const Vector3d p_WB =
Vector3d(2, 3, 4).normalized() * (kCenterDistance + kEps);
X_WGs[id_B].set_translation(p_WB);
engine.UpdateWorldPoses(X_WGs);
const auto results =
engine.ComputeSignedDistancePairwiseClosestPoints(X_WGs, kMaxDistance);
EXPECT_EQ(results.size(), 0);
}
}
// Tests the computation of signed distance for a single geometry pair. Confirms
// successful case as well as failure case.
GTEST_TEST(ProximityEngineTests, SignedDistancePairClosestPoint) {
ProximityEngine<double> engine;
const GeometryId id_A = GeometryId::get_new_id();
const GeometryId id_B = GeometryId::get_new_id();
const GeometryId bad_id = GeometryId::get_new_id();
unordered_map<GeometryId, RigidTransformd> X_WGs{
{id_A, RigidTransformd::Identity()}, {id_B, RigidTransformd::Identity()}};
const double radius = 0.5;
Sphere sphere{radius};
engine.AddDynamicGeometry(sphere, {}, id_A);
engine.AddDynamicGeometry(sphere, {}, id_B);
const double kDistance = 1.0;
const double kCenterDistance = kDistance + radius + radius;
// Displace B the desired distance in an arbitrary direction.
const Vector3d p_WB = Vector3d(2, 3, 4).normalized() * kCenterDistance;
X_WGs[id_B].set_translation(p_WB);
engine.UpdateWorldPoses(X_WGs);
// Case: good case produces the correct value.
{
const SignedDistancePair<double> result =
engine.ComputeSignedDistancePairClosestPoints(id_A, id_B, X_WGs);
EXPECT_EQ(result.id_A, id_A);
EXPECT_EQ(result.id_B, id_B);
EXPECT_NEAR(result.distance, kDistance,
std::numeric_limits<double>::epsilon());
// We're not testing *all* the fields. The callback is setting the fields,
// we assume if ids and distance are correct, the previously tested callback
// code does it all correctly.
}
// Case: the first id is invalid.
{
DRAKE_EXPECT_THROWS_MESSAGE(
engine.ComputeSignedDistancePairClosestPoints(bad_id, id_B, X_WGs),
fmt::format("The geometry given by id {} does not reference .+ used in "
"a signed distance query", bad_id));
}
// Case: the second id is invalid.
{
DRAKE_EXPECT_THROWS_MESSAGE(
engine.ComputeSignedDistancePairClosestPoints(id_A, bad_id, X_WGs),
fmt::format("The geometry given by id {} does not reference .+ used in "
"a signed distance query", bad_id));
}
// Case: the distance is evaluated even though the pair is filtered.
{
// I know the GeometrySet only has id_A and id_B, so I'll construct the
// extracted set by hand.
auto extract_ids = [id_A, id_B](const GeometrySet&) {
return std::unordered_set<GeometryId>{id_A, id_B};
};
engine.collision_filter().Apply(
CollisionFilterDeclaration().ExcludeWithin(GeometrySet{id_A, id_B}),
extract_ids, false /* is_invariant */);
EXPECT_NO_THROW(
engine.ComputeSignedDistancePairClosestPoints(id_A, id_B, X_WGs));
}
}
// ComputeSignedDistanceToPoint tests
// Test the broad-phase part of ComputeSignedDistanceToPoint.
// Confirms that non-positve thresholds produce the right value. Creates two
// penetrating spheres: A & B. The query point is *inside* the intersection of
// A and B. We confirm that query tolerance of 0, returns two results and that
// a tolerance of penetration depth + epsilon likewise returns two results, and
// depth - epsilon omits everything.
GTEST_TEST(ProximityEngineTests, SignedDistanceToPointNonPositiveThreshold) {
ProximityEngine<double> engine;
const double kRadius = 0.5;
const double kPenetration = kRadius * 0.1;
const GeometryId id_A = GeometryId::get_new_id();
const GeometryId id_B = GeometryId::get_new_id();
const unordered_map<GeometryId, RigidTransformd> X_WGs{
{id_A,
RigidTransformd{Translation3d{-kRadius + 0.5 * kPenetration, 0, 0}}},
{id_B,
RigidTransformd{Translation3d{kRadius - 0.5 * kPenetration, 0, 0}}}};
Sphere sphere{kRadius};
engine.AddDynamicGeometry(sphere, {}, id_A);
engine.AddDynamicGeometry(sphere, {}, id_B);
engine.UpdateWorldPoses(X_WGs);
const Vector3d p_WQ{0, 0, 0};
std::vector<SignedDistanceToPoint<double>> results_all =
engine.ComputeSignedDistanceToPoint(p_WQ, X_WGs, kInf);
EXPECT_EQ(results_all.size(), 2u);
std::vector<SignedDistanceToPoint<double>> results_zero =
engine.ComputeSignedDistanceToPoint(p_WQ, X_WGs, 0);
EXPECT_EQ(results_zero.size(), 2u);
const double kEps = std::numeric_limits<double>::epsilon();
std::vector<SignedDistanceToPoint<double>> results_barely_in =
engine.ComputeSignedDistanceToPoint(p_WQ, X_WGs,
-kPenetration * 0.5 + kEps);
EXPECT_EQ(results_barely_in.size(), 2u);
std::vector<SignedDistanceToPoint<double>> results_barely_out =
engine.ComputeSignedDistanceToPoint(p_WQ, X_WGs,
-kPenetration * 0.5 - kEps);
EXPECT_EQ(results_barely_out.size(), 0u);
}
// We put two small spheres with radius 0.1 centered at (1,1,1) and
// (-1,-1,-1). The query point Q will be at (3,3,3), so we can test that our
// code does call computeAABB() of the query point (by default, its AABB is
// [0,0]x[0,0]x[0,0]). We test several values of the distance threshold to
// include different numbers of spheres.
//
// Q query point
//
//
// y
// | o first small sphere
// |
// +----- x
//
// o second small sphere
//
GTEST_TEST(SignedDistanceToPointBroadphaseTest, MultipleThreshold) {
ProximityEngine<double> engine;
unordered_map<GeometryId, RigidTransformd> X_WGs;
const double radius = 0.1;
const Vector3d center1(1., 1., 1.);
const Vector3d center2(-1, -1, -1.);
for (const Vector3d& p_WG : {center1, center2}) {
const RigidTransformd X_WG(Translation3d{p_WG});
const GeometryId id = GeometryId::get_new_id();
X_WGs[id] = X_WG;
engine.AddAnchoredGeometry(Sphere(radius), X_WG, id);
}
const Vector3d p_WQ(3., 3., 3.);