-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathdetail_scene_graph_test.cc
1350 lines (1251 loc) · 51 KB
/
detail_scene_graph_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/multibody/parsing/detail_scene_graph.h"
#include <limits>
#include <memory>
#include <optional>
#include <sstream>
#include "fmt/ostream.h"
#include <gtest/gtest.h>
#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/geometry/geometry_instance.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/geometry/scene_graph.h"
#include "drake/math/roll_pitch_yaw.h"
#include "drake/math/rotation_matrix.h"
#include "drake/multibody/parsing/detail_common.h"
#include "drake/multibody/parsing/detail_ignition.h"
namespace drake {
namespace multibody {
namespace internal {
namespace {
using Eigen::Matrix3d;
using Eigen::Vector3d;
using geometry::Box;
using geometry::Capsule;
using geometry::Convex;
using geometry::Cylinder;
using geometry::Ellipsoid;
using geometry::GeometryInstance;
using geometry::HalfSpace;
using geometry::IllustrationProperties;
using geometry::Mesh;
using geometry::ProximityProperties;
using geometry::SceneGraph;
using geometry::Shape;
using geometry::Sphere;
using math::RigidTransformd;
using math::RollPitchYaw;
using math::RotationMatrix;
using multibody::internal::MakeCoulombFrictionFromSdfCollisionOde;
using multibody::internal::MakeGeometryInstanceFromSdfVisual;
using multibody::internal::MakeGeometryPoseFromSdfCollision;
using multibody::internal::MakeShapeFromSdfGeometry;
using multibody::internal::MakeVisualPropertiesFromSdfVisual;
using std::make_unique;
using std::unique_ptr;
using systems::Context;
using systems::LeafSystem;
// Helper to create an sdf::Geometry object from its SDF specification given
// as a string. Example of what the string should contain:
// <cylinder>
// <radius>0.5</radius>
// <length>1.2</length>
// </cylinder>
// and similarly for other SDF geometries.
unique_ptr<sdf::Geometry> MakeSdfGeometryFromString(
const std::string& geometry_spec) {
const std::string sdf_str =
"<?xml version='1.0'?>"
"<sdf version='1.7'>"
" <model name='my_model'>"
" <link name='link'>"
" <visual name='link_visual'>"
" <geometry>"
+ geometry_spec +
" </geometry>"
" </visual>"
" </link>"
" </model>"
"</sdf>";
sdf::SDFPtr sdf_parsed(new sdf::SDF());
sdf::init(sdf_parsed);
sdf::readString(sdf_str, sdf_parsed);
sdf::ElementPtr geometry_element =
sdf_parsed->Root()->GetElement("model")->
GetElement("link")->GetElement("visual")->GetElement("geometry");
auto sdf_geometry = make_unique<sdf::Geometry>();
sdf_geometry->Load(geometry_element);
return sdf_geometry;
}
// Helper to create an sdf::Visual object from its SDF specification given
// as a string. Example of what the string should contain:
// <visual name = 'some_link_visual'>
// <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>
// <geometry>
// <cylinder>
// <radius>0.5</radius>
// <length>1.2</length>
// </cylinder>
// </geometry>
// </visual>
unique_ptr<sdf::Visual> MakeSdfVisualFromString(
const std::string& visual_spec) {
const std::string sdf_str =
"<?xml version='1.0'?>"
"<sdf version='1.7'>"
" <model name='my_model'>"
" <link name='link'>"
+ visual_spec +
" </link>"
" </model>"
"</sdf>";
sdf::SDFPtr sdf_parsed(new sdf::SDF());
sdf::init(sdf_parsed);
sdf::readString(sdf_str, sdf_parsed);
sdf::ElementPtr visual_element =
sdf_parsed->Root()->GetElement("model")->
GetElement("link")->GetElement("visual");
auto sdf_visual = make_unique<sdf::Visual>();
sdf_visual->Load(visual_element);
return sdf_visual;
}
// Helper to create an sdf::Collision object from its SDF specification given
// as a string. Example of what the string should contain:
// <collision name = 'some_link_collision'>
// <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>
// <geometry>
// <cylinder>
// <radius>0.5</radius>
// <length>1.2</length>
// </cylinder>
// </geometry>
// <drake_friction>
// <static_friction>0.8</static_friction>
// <dynamic_friction>0.3</dynamic_friction>
// </drake_friction>
// </collision>
unique_ptr<sdf::Collision> MakeSdfCollisionFromString(
const std::string& collision_spec) {
const std::string sdf_str =
"<?xml version='1.0'?>"
"<sdf version='1.7'>"
" <model name='my_model'>"
" <link name='link'>"
+ collision_spec +
" </link>"
" </model>"
"</sdf>";
sdf::SDFPtr sdf_parsed(new sdf::SDF());
sdf::init(sdf_parsed);
sdf::readString(sdf_str, sdf_parsed);
sdf::ElementPtr collision_element =
sdf_parsed->Root()->GetElement("model")->
GetElement("link")->GetElement("collision");
auto sdf_collision = make_unique<sdf::Collision>();
sdf_collision->Load(collision_element);
return sdf_collision;
}
// Define a pass-through functor for testing.
std::string NoopResolveFilename(std::string filename) { return filename; }
// Verify MakeShapeFromSdfGeometry returns nullptr when we specify an <empty>
// sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeEmptyFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry =
MakeSdfGeometryFromString("<empty/>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
EXPECT_EQ(shape, nullptr);
}
// Verify MakeShapeFromSdfGeometry can make a box from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeBoxFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<box>"
" <size>1.0 2.0 3.0</size>"
"</box>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Box* box = dynamic_cast<const Box*>(shape.get());
ASSERT_NE(box, nullptr);
EXPECT_EQ(box->size(), Vector3d(1.0, 2.0, 3.0));
}
// Verify MakeShapeFromSdfGeometry can make a capsule from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeCapsuleFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<drake:capsule>"
" <radius>0.5</radius>"
" <length>1.2</length>"
"</drake:capsule>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Capsule* capsule = dynamic_cast<const Capsule*>(shape.get());
ASSERT_NE(capsule, nullptr);
EXPECT_EQ(capsule->radius(), 0.5);
EXPECT_EQ(capsule->length(), 1.2);
}
// Verify MakeShapeFromSdfGeometry checks for invalid capsules.
GTEST_TEST(SceneGraphParserDetail, CheckInvalidCapsules) {
unique_ptr<sdf::Geometry> no_radius_geometry = MakeSdfGeometryFromString(
"<drake:capsule>"
" <length>1.2</length>"
"</drake:capsule>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeShapeFromSdfGeometry(*no_radius_geometry, NoopResolveFilename),
std::runtime_error,
"Element <radius> is required within element <drake:capsule>.");
unique_ptr<sdf::Geometry> no_length_geometry = MakeSdfGeometryFromString(
"<drake:capsule>"
" <radius>0.5</radius>"
"</drake:capsule>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeShapeFromSdfGeometry(*no_length_geometry, NoopResolveFilename),
std::runtime_error,
"Element <length> is required within element <drake:capsule>.");
}
// Verify MakeShapeFromSdfGeometry can make a cylinder from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeCylinderFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<cylinder>"
" <radius>0.5</radius>"
" <length>1.2</length>"
"</cylinder>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Cylinder* cylinder = dynamic_cast<const Cylinder*>(shape.get());
ASSERT_NE(cylinder, nullptr);
EXPECT_EQ(cylinder->radius(), 0.5);
EXPECT_EQ(cylinder->length(), 1.2);
}
// Verify MakeShapeFromSdfGeometry can make an ellipsoid from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeEllipsoidFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<drake:ellipsoid>"
" <a>0.5</a>"
" <b>1.2</b>"
" <c>0.9</c>"
"</drake:ellipsoid>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Ellipsoid* ellipsoid = dynamic_cast<const Ellipsoid*>(shape.get());
ASSERT_NE(ellipsoid, nullptr);
EXPECT_EQ(ellipsoid->a(), 0.5);
EXPECT_EQ(ellipsoid->b(), 1.2);
EXPECT_EQ(ellipsoid->c(), 0.9);
}
// Verify MakeShapeFromSdfGeometry checks for invalid ellispoids.
GTEST_TEST(SceneGraphParserDetail, CheckInvalidEllipsoids) {
unique_ptr<sdf::Geometry> no_a_geometry = MakeSdfGeometryFromString(
"<drake:ellipsoid>"
" <b>1.2</b>"
" <c>0.9</c>"
"</drake:ellipsoid>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeShapeFromSdfGeometry(*no_a_geometry, NoopResolveFilename),
std::runtime_error,
"Element <a> is required within element <drake:ellipsoid>.");
unique_ptr<sdf::Geometry> no_b_geometry = MakeSdfGeometryFromString(
"<drake:ellipsoid>"
" <a>0.5</a>"
" <c>0.9</c>"
"</drake:ellipsoid>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeShapeFromSdfGeometry(*no_b_geometry, NoopResolveFilename),
std::runtime_error,
"Element <b> is required within element <drake:ellipsoid>.");
unique_ptr<sdf::Geometry> no_c_geometry = MakeSdfGeometryFromString(
"<drake:ellipsoid>"
" <a>0.5</a>"
" <b>1.2</b>"
"</drake:ellipsoid>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeShapeFromSdfGeometry(*no_c_geometry, NoopResolveFilename),
std::runtime_error,
"Element <c> is required within element <drake:ellipsoid>.");
}
// Verify MakeShapeFromSdfGeometry can make a sphere from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeSphereFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<sphere>"
" <radius>0.5</radius>"
"</sphere>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Sphere* sphere = dynamic_cast<const Sphere*>(shape.get());
ASSERT_NE(sphere, nullptr);
EXPECT_EQ(sphere->radius(), 0.5);
}
// Verify MakeShapeFromSdfGeometry can make a half space from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeHalfSpaceFromSdfGeometry) {
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<plane>"
" <normal>1.0 0.0 0.0</normal>"
" <size>1.0 1.0 1.0</size>"
"</plane>");
// MakeShapeFromSdfGeometry() ignores <normal> and <size> to create the
// HalfSpace. Therefore we only verify it created the right object.
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
EXPECT_TRUE(dynamic_cast<const HalfSpace*>(shape.get()) != nullptr);
}
// Verify MakeShapeFromSdfGeometry can make a mesh from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeMeshFromSdfGeometry) {
// TODO(amcastro-tri): Be warned, the result of this test might (should)
// change as we add support allowing to specify paths relative to the SDF file
// location.
const std::string absolute_file_path = "path/to/some/mesh.obj";
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<mesh>"
" <uri>" + absolute_file_path + "</uri>"
" <scale> 3 3 3 </scale>"
"</mesh>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Mesh* mesh = dynamic_cast<const Mesh*>(shape.get());
ASSERT_NE(mesh, nullptr);
EXPECT_EQ(mesh->filename(), absolute_file_path);
EXPECT_EQ(mesh->scale(), 3);
}
// Verify MakeShapeFromSdfGeometry can make a convex mesh from an sdf::Geometry.
GTEST_TEST(SceneGraphParserDetail, MakeConvexFromSdfGeometry) {
const std::string absolute_file_path = "path/to/some/mesh.obj";
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<mesh xmlns:drake='drake.mit.edu'>"
" <drake:declare_convex/>"
" <uri>" + absolute_file_path + "</uri>"
" <scale> 3 3 3 </scale>"
"</mesh>");
unique_ptr<Shape> shape = MakeShapeFromSdfGeometry(
*sdf_geometry, NoopResolveFilename);
const Convex* convex = dynamic_cast<const Convex*>(shape.get());
ASSERT_NE(convex, nullptr);
EXPECT_EQ(convex->filename(), absolute_file_path);
EXPECT_EQ(convex->scale(), 3);
}
// Verify MakeGeometryInstanceFromSdfVisual can make a GeometryInstance from an
// sdf::Visual.
// Since we test MakeShapeFromSdfGeometry separately, there is no need to unit
// test every combination of a <visual> with a different <geometry>.
GTEST_TEST(SceneGraphParserDetail, MakeGeometryInstanceFromSdfVisual) {
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name = 'some_link_visual'>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <cylinder>"
" <radius>0.5</radius>"
" <length>1.2</length>"
" </cylinder>"
" </geometry>"
"</visual>");
unique_ptr<GeometryInstance> geometry_instance =
MakeGeometryInstanceFromSdfVisual(
*sdf_visual, NoopResolveFilename,
ToRigidTransform(sdf_visual->RawPose()));
const RigidTransformd X_LC(geometry_instance->pose());
// These are the expected values as specified by the string above.
const RollPitchYaw<double> expected_rpy(3.14, 6.28, 1.57);
const RotationMatrix<double> R_LC_expected(expected_rpy);
const Vector3d p_LCo_expected(1.0, 2.0, 3.0);
// Verify results to precision given by kTolerance.
const double kTolerance = 10 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(X_LC.rotation().IsNearlyEqualTo(R_LC_expected, kTolerance));
EXPECT_TRUE(CompareMatrices(X_LC.translation(), p_LCo_expected,
kTolerance, MatrixCompareType::relative));
}
// Confirms the failure conditions for SDFormat. SceneGraph requirements on
// geometry names are supposed to mirror the SDFormat behavior. If these tests
// no longer fail, the requirements in SceneGraph should become more relaxed.
// Alternatively, if more failure modes are learned, they should be encoded
// here and in the SceneGraph logic (start at the documentation of
// GeometryInstace).
// Note: This is only tested for visual geometries, but the same requirements
// are assumed for collision geometries.
GTEST_TEST(SceneGraphParserDetail, VisualGeometryNameRequirements) {
// It is necessary to do a full, deep parse from the root to reveal *all*
// of the failure modes.
// A fmt::format-compatible string for testing various permutations of visual
// names.
const std::string visual_tag =
"<visual name='{}'>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <cylinder>"
" <radius>0.5</radius>"
" <length>1.2</length>"
" </cylinder>"
" </geometry>"
"</visual>";
auto valid_parse = [](const std::string& visual_str) -> bool {
const std::string sdf_str = fmt::format(
"<?xml version='1.0'?>"
"<sdf version='1.7'>"
" <model name='my_model'>"
" <link name='link'>{}"
" </link>"
" </model>"
"</sdf>",
visual_str);
sdf::Root root;
auto errors = root.LoadSdfString(sdf_str);
return errors.empty();
};
// Allowable naming.
// Case: control group - a simple valid name.
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, "visual")));
// Case: Valid name with leading whitespace.
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, " visual")));
// Case: Valid name with trailing whitespace.
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, "visual ")));
// These whitespace characters are *not* considered to be whitespace by SDF.
std::vector<std::pair<char, std::string>> ignored_whitespace{
{'\v', "\\v"}, {'\f', "\\f"}};
for (const auto& pair : ignored_whitespace) {
// Case: Whitespace-only name.
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, pair.first)))
<< "Failed on " << pair.second;
}
{
// Case: Same name for two different geometry types (collision vs visual).
const std::string collision_tag =
"<collision name='thing'>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <sphere/>"
" </geometry>"
"</collision>";
EXPECT_TRUE(valid_parse(fmt::format(visual_tag, "thing") + collision_tag));
}
// Invalid naming
{
// Case: Missing name element.
const std::string missing_name_parameter =
"<visual>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <cylinder>"
" <radius>0.5</radius>"
" <length>1.2</length>"
" </cylinder>"
" </geometry>"
"</visual>";
EXPECT_FALSE(valid_parse(missing_name_parameter));
}
// Case: Empty name element.
EXPECT_FALSE(valid_parse(fmt::format(visual_tag, "")));
std::vector<std::pair<char, std::string>> invalid_whitespace{{' ', "space"},
{'\t', "\\t"}};
for (const auto& pair : invalid_whitespace) {
// Case: Whitespace-only name.
EXPECT_FALSE(valid_parse(fmt::format(visual_tag, pair.first)))
<< "Failed on " << pair.second;
}
// Case: Duplicate names.
EXPECT_FALSE(valid_parse(fmt::format(visual_tag, "visual") +
fmt::format(visual_tag, "visual")));
// Case: Duplicate names which arise from trimming whitespace.
EXPECT_FALSE(valid_parse(fmt::format(visual_tag, "visual ") +
fmt::format(visual_tag, " visual")));
}
// Verify MakeGeometryInstanceFromSdfVisual can make a GeometryInstance from an
// sdf::Visual with a <plane> geometry.
// We test this case separately since, while geometry::HalfSpace is defined in a
// canonical frame C whose pose needs to be specified at a GeometryInstance
// level, the SDF specification does not define this pose at the <geometry>
// level but at the <visual> (or <collision>) level.
GTEST_TEST(SceneGraphParserDetail, MakeHalfSpaceGeometryInstanceFromSdfVisual) {
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name = 'some_link_visual'>"
" <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>"
" <geometry>"
" <plane>"
" <normal>1.0 2.0 3.0</normal>"
" </plane>"
" </geometry>"
"</visual>");
unique_ptr<GeometryInstance> geometry_instance =
MakeGeometryInstanceFromSdfVisual(
*sdf_visual, NoopResolveFilename,
ToRigidTransform(sdf_visual->RawPose()));
// Verify we do have a plane geometry.
const HalfSpace* shape =
dynamic_cast<const HalfSpace*>(&geometry_instance->shape());
ASSERT_TRUE(shape != nullptr);
// The expected coordinates of the normal vector in the link frame L.
const Vector3d normal_L_expected = Vector3d(1.0, 2.0, 3.0).normalized();
// The expected orientation of the canonical frame C (in which the plane's
// normal aligns with Cz) in the link frame L.
const RotationMatrix<double> R_LC_expected =
HalfSpace::MakePose(normal_L_expected, Vector3d::Zero()).rotation();
// Retrieve the GeometryInstance pose as parsed from the sdf::Visual.
const RotationMatrix<double> R_LC = geometry_instance->pose().rotation();
const Vector3d normal_L = R_LC.col(2);
// Verify results to precision given by kTolerance.
const double kTolerance = 10 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(R_LC.IsNearlyEqualTo(R_LC_expected, kTolerance));
EXPECT_TRUE(CompareMatrices(normal_L, normal_L_expected,
kTolerance, MatrixCompareType::relative));
}
// Verify MakeSdfVisualFromString() returns nullptr when the visual specifies
// an <empty/> geometry.
GTEST_TEST(SceneGraphParserDetail, MakeEmptyGeometryInstanceFromSdfVisual) {
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name = 'some_link_visual'>"
" <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>"
" <geometry>"
" <empty/>"
" </geometry>"
"</visual>");
unique_ptr<GeometryInstance> geometry_instance =
MakeGeometryInstanceFromSdfVisual(
*sdf_visual, NoopResolveFilename,
ToRigidTransform(sdf_visual->RawPose()));
EXPECT_EQ(geometry_instance, nullptr);
}
// Reports if the indicated typed geometry property matches expectations.
// The expectation is given by an optional `expected_value`. If nullopt, we
// expect the property to be absent. If provided, we expect the property to
// exist with the given type and have the same value.
template <typename T, typename Compare>
::testing::AssertionResult HasExpectedProperty(
const char* group, const char* property, std::optional<T> expected_value,
const IllustrationProperties& properties, Compare matches) {
::testing::AssertionResult failure = ::testing::AssertionFailure();
const bool has_property = properties.HasProperty(group, property);
if (expected_value.has_value()) {
if (has_property) {
// This will throw if the property is of the wrong type.
const T& value = properties.GetProperty<T>(group, property);
if (matches(value, *expected_value)) {
return ::testing::AssertionSuccess();
} else {
failure << "\nIncorrect values for ('" << group << "', " << property
<< "'):" << "\n expected: " << (*expected_value)
<< "\n found: " << value;
}
} else {
failure << "\n missing expected property ('" << group << "', '"
<< property << "')";
}
} else {
if (!has_property) return ::testing::AssertionSuccess();
failure << "\n found unexpected property ('" << group << "', '" << property
<< "')";
}
failure << "\n";
return failure;
}
// Verify visual material parsing: default for unspecified, and diffuse color
// given where specified in the SDF.
GTEST_TEST(SceneGraphParserDetail, ParseVisualMaterial) {
using Eigen::Vector4d;
// Searches the illustration properties for an optional phong material
// specification with optional color values.
auto expect_phong = [](const IllustrationProperties& dut,
bool must_have_group,
const std::optional<Vector4d> diffuse,
const std::optional<Vector4d> specular,
const std::optional<Vector4d> ambient,
const std::optional<Vector4d> emissive,
const std::optional<std::string> diffuse_map)
-> ::testing::AssertionResult {
::testing::AssertionResult failure = ::testing::AssertionFailure();
failure << "\nKnown failure conditions:";
bool success = true;
auto test_color = [&failure, &success, &dut](
const char* name,
const std::optional<Vector4d> ref_color) {
auto result =
HasExpectedProperty("phong", name, ref_color, dut,
[](const Vector4d& a, const Vector4d& b) {
return static_cast<bool>(CompareMatrices(a, b));
});
if (!result) {
failure << result.message();
success = false;
}
};
if (must_have_group) {
if (dut.HasGroup("phong")) {
test_color("diffuse", diffuse);
test_color("specular", specular);
test_color("ambient", ambient);
test_color("emissive", emissive);
auto result = HasExpectedProperty(
"phong", "diffuse_map", diffuse_map, dut,
[](const std::string& a, const std::string& b) { return a == b; });
if (!result) {
failure << result;
success = false;
}
} else {
failure << "\n missing the expected 'phong' group";
success = false;
}
} else {
if (dut.HasGroup("phong")) {
failure << "\n found unexpected 'phong' group";
success = false;
}
}
if (success) {
return ::testing::AssertionSuccess();
} else {
failure << "\n";
return failure;
}
};
// Builds a visual XML tag with an optional <material> tag and optional
// color values.
auto make_xml = [](bool has_material, Vector4d* diffuse, Vector4d* specular,
Vector4d* ambient, Vector4d* emissive,
const std::string& texture_name) {
std::stringstream ss;
ss << "<visual name='some_link_visual'>"
<< " <pose>0 0 0 0 0 0</pose>"
<< " <geometry>"
<< " <sphere>"
<< " <radius>1</radius>"
<< " </sphere>"
<< " </geometry>";
if (has_material) {
auto write_color = [&ss](const char* name, const Vector4d* color) {
if (color) {
const Vector4d& c = *color;
ss << fmt::format(" <{0}>{1} {2} {3} {4}</{0}>", name,
c(0), c(1), c(2), c(3));
}
};
ss << " <material>";
if (!texture_name.empty()) {
ss << " <drake:diffuse_map>" << texture_name
<< "</drake:diffuse_map>";
}
write_color("diffuse", diffuse);
write_color("specular", specular);
write_color("ambient", ambient);
write_color("emissive", emissive);
ss << " </material>";
}
ss << "</visual>";
return ss.str();
};
// We need a root directory to an actually existing file we can reference.
const std::string file_path = FindResourceOrThrow(
"drake/multibody/parsing/test/urdf_parser_test/empty.png");
const std::string root_dir =
filesystem::path(file_path).parent_path().string();
// Case: No material defined -- empty illustration properties.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(false, nullptr, nullptr, nullptr, nullptr, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, false, {}, {}, {}, {}, {}));
}
// Case: Material tag defined, but no material properties -- empty
// illustration properties.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, nullptr, nullptr, nullptr, nullptr, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, false, {}, {}, {}, {}, {}));
}
Vector4<double> diffuse{0.25, 0.5, 0.75, 1.0};
Vector4<double> specular{0.5, 0.75, 1.0, 0.25};
Vector4<double> ambient{0.75, 1.0, 0.25, 0.5};
Vector4<double> emissive{1.0, 0.25, 0.5, 0.75};
// Case: Only valid diffuse material.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, &diffuse, nullptr, nullptr, nullptr, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, true, diffuse, {}, {}, {}, {}));
}
// Case: Only valid specular defined.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, nullptr, &specular, nullptr, nullptr, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, true, {}, specular, {}, {}, {}));
}
// Case: Only valid ambient defined.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, nullptr, nullptr, &ambient, nullptr, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, true, {}, {}, ambient, {}, {}));
}
// Case: Only valid emissive defined.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, nullptr, nullptr, nullptr, &emissive, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(expect_phong(material, true, {}, {}, {}, emissive, {}));
}
// Case: All four.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, &diffuse, &specular, &ambient, &emissive, ""));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(
expect_phong(material, true, diffuse, specular, ambient, emissive, {}));
}
// Case: With diffuse map.
{
// Note: we only test with a local map; we rely on the tests for resolving
// URIs to do the right thing with other URI formats.
const std::string kLocalMap = "empty.png";
const std::string xml =
make_xml(true, &diffuse, &specular, &ambient, &emissive, kLocalMap);
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
make_xml(true, &diffuse, &specular, &ambient, &emissive, kLocalMap));
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
// Note: The "no-op" filename resolver will just return kLocalMap as the
// property name.
EXPECT_TRUE(expect_phong(material, true, diffuse, specular, ambient,
emissive, kLocalMap));
}
// TODO(SeanCurtis-TRI): The following tests capture current behavior for
// sdformat. The behavior isn't necessarily desirable and an issue has been
// filed.
// https://bitbucket.org/osrf/sdformat/issues/193/using-element-get-has-surprising-defaults
// When this issue gets resolved, modify these tests accordingly.
// sdformat maps the diffuse values into a `Color` using the following rules:
// 1. Truncate to no more than four values (more than 4 values are simply
// ignored).
// 2. If fewer than four, use 1 for a default alpha value and zero for
// default r, g, b values.
// Case: Too many channel values -- truncate.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0.25 1 0.5 0.25 2</diffuse>"
" </material>"
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
Vector4<double> expected_diffuse{0.25, 1, 0.5, 0.25};
EXPECT_TRUE(expect_phong(material, true, expected_diffuse, {}, {}, {}, {}));
}
// Case: Too few channel values -- fill in with 0 for b and 1 for alpha.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0 1</diffuse>"
" </material>"
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
Vector4<double> expected_diffuse{0, 1, 1, 1};
EXPECT_TRUE(expect_phong(material, true, expected_diffuse, {}, {}, {}, {}));
}
// Case: Values out of range:
// A (alpha) simply gets clamped to the range [0, 1]
// For each individual element in R, G, B:
// Negative values are set to zero.
// Values > 1 are divided by 255
// This test *must* show that these rules (from libsdformat) do not
// guarantee valid values.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>-0.1 255 65025 2</diffuse>"
" </material>"
"</visual>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename),
std::runtime_error,
"All values must be within the range \\[0, 1\\]. Values provided: "
"\\(r=0(\\.0)?, g=1(\\.0)?, b=255(\\.0)?, a=1(\\.0)?\\)");
}
}
// Confirms that the <drake:accepting_renderer> tag gets properly parsed.
GTEST_TEST(SceneGraphParseDetail, AcceptingRenderers) {
const std::string group = "renderer";
const std::string property = "accepting";
// Case: no <drake:accepting_renderer> tag.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0.25 1 0.5 0.25 2</diffuse>"
" </material>"
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_FALSE(material.HasProperty(group, property));
}
// Case: single <drake:accepting_renderer> tag.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0.25 1 0.5 0.25 2</diffuse>"
" </material>"
" <drake:accepting_renderer>renderer1</drake:accepting_renderer>"
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(material.HasProperty(group, property));
const auto& names =
material.GetProperty<std::set<std::string>>(group, property);
EXPECT_EQ(names.size(), 1);
EXPECT_EQ(names.count("renderer1"), 1);
}
// Case: Multiple <drake:accepting_renderer> tag.
{
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0.25 1 0.5 0.25 2</diffuse>"
" </material>"
" <drake:accepting_renderer>renderer1</drake:accepting_renderer>"
" <drake:accepting_renderer>renderer2</drake:accepting_renderer>"
"</visual>");
IllustrationProperties material =
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename);
EXPECT_TRUE(material.HasProperty(group, property));
const auto& names =
material.GetProperty<std::set<std::string>>(group, property);
EXPECT_EQ(names.size(), 2);
EXPECT_EQ(names.count("renderer1"), 1);
EXPECT_EQ(names.count("renderer2"), 1);
}
// Case: Missing names throws exception.
unique_ptr<sdf::Visual> sdf_visual = MakeSdfVisualFromString(
"<visual name='some_link_visual'>"
" <pose>0 0 0 0 0 0</pose>"
" <geometry>"
" <sphere>"
" <radius>1</radius>"
" </sphere>"
" </geometry>"
" <material>"
" <diffuse>0.25 1 0.5 0.25 2</diffuse>"
" </material>"
" <drake:accepting_renderer> </drake:accepting_renderer>"
"</visual>");
DRAKE_EXPECT_THROWS_MESSAGE(
MakeVisualPropertiesFromSdfVisual(*sdf_visual, NoopResolveFilename),
std::runtime_error,
"<drake:accepting_renderer> tag given without any name");
}
// Verify MakeGeometryPoseFromSdfCollision() makes the pose X_LG of geometry
// frame G in the link frame L.
// Since we test MakeShapeFromSdfGeometry separately, there is no need to unit
// test every combination of a <collision> with a different <geometry>.
GTEST_TEST(SceneGraphParserDetail, MakeGeometryPoseFromSdfCollision) {
unique_ptr<sdf::Collision> sdf_collision = MakeSdfCollisionFromString(
"<collision name = 'some_link_collision'>"
" <pose>1.0 2.0 3.0 3.14 6.28 1.57</pose>"
" <geometry>"
" <sphere/>"
" </geometry>"
"</collision>");
const RigidTransformd X_LG = MakeGeometryPoseFromSdfCollision(
*sdf_collision, ToRigidTransform(sdf_collision->RawPose()));
// These are the expected values as specified by the string above.
const RollPitchYaw<double> expected_rpy(3.14, 6.28, 1.57);
const RotationMatrix<double> R_LG_expected(expected_rpy);
const Vector3d p_LGo_expected(1.0, 2.0, 3.0);
// Verify results to precision given by kTolerance.
const double kTolerance = 10 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(X_LG.rotation().IsNearlyEqualTo(R_LG_expected, kTolerance));
EXPECT_TRUE(CompareMatrices(X_LG.translation(), p_LGo_expected, kTolerance,
MatrixCompareType::relative));
}
// Verify MakeGeometryPoseFromSdfCollision can make the pose X_LG of the
// geometry frame G in the link frame L when the specified shape is a plane.
// We test this case separately since, while geometry::HalfSpace is defined in a
// canonical frame C whose pose needs to be specified at a GeometryInstance
// level, the SDF specification does not define this pose at the <geometry>
// level but at the <collision> level.
GTEST_TEST(SceneGraphParserDetail,
MakeGeometryPoseFromSdfCollisionForHalfSpace) {
unique_ptr<sdf::Collision> sdf_collision = MakeSdfCollisionFromString(
"<collision name = 'some_link_collision'>"
" <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>"
" <geometry>"
" <plane>"
" <normal>1.0 2.0 3.0</normal>"
" </plane>"
" </geometry>"
"</collision>");
const RigidTransformd X_LG = MakeGeometryPoseFromSdfCollision(
*sdf_collision, ToRigidTransform(sdf_collision->RawPose()));
// The expected coordinates of the normal vector in the link frame L.