forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgeometry_state.cc
1810 lines (1616 loc) · 68.1 KB
/
geometry_state.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/geometry_state.h"
#include <algorithm>
#include <functional>
#include <memory>
#include <string>
#include <utility>
#include <fmt/format.h>
#include "drake/common/autodiff.h"
#include "drake/common/default_scalars.h"
#include "drake/common/extract_double.h"
#include "drake/common/text_logging.h"
#include "drake/geometry/geometry_frame.h"
#include "drake/geometry/geometry_instance.h"
#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/proximity_engine.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/geometry/render/render_engine.h"
#include "drake/geometry/utilities.h"
#include "drake/math/autodiff_gradient.h"
namespace drake {
namespace geometry {
using internal::convert_to_double;
using internal::FrameNameSet;
using internal::HydroelasticType;
using internal::InternalFrame;
using internal::InternalGeometry;
using internal::ProximityEngine;
using math::RigidTransform;
using math::RigidTransformd;
using render::ColorRenderCamera;
using render::DepthRenderCamera;
using std::make_pair;
using std::make_unique;
using std::move;
using std::set;
using std::string;
using std::swap;
using std::to_string;
using std::unordered_set;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
//-----------------------------------------------------------------------------
// These utility methods help streamline the desired semantics of map lookups.
// We want to search for a key and throw an exception (with a meaningful
// message) if not found.
// Helper method for consistently determining the presence of a key in a
// container and throwing a consistent exception type if absent.
// Searches for a key value in a "findable" object. To be findable, the source
// must have find(const Key&) and end() methods that return types that can
// be equality compared, such that if they are equal, the key is *not* present
// in the source. The exception message is produced by the given functor,
// make_message().
template <class Key, class Findable>
void FindOrThrow(const Key& key, const Findable& source,
const std::function<std::string()>& make_message) {
if (source.find(key) == source.end()) throw std::logic_error(make_message());
}
// Definition of error message for a missing key lookup.
template <class Key>
std::string get_missing_id_message(const Key& key) {
// TODO(SeanCurtis-TRI): Use NiceTypeName to get the key name.
return "Error in map look up of unexpected key type";
}
// The look up and error-throwing method for const values.
template <class Key, class Value>
const Value& GetValueOrThrow(const Key& key,
const std::unordered_map<Key, Value>& map) {
auto itr = map.find(key);
if (itr != map.end()) {
return itr->second;
}
throw std::logic_error(get_missing_id_message(key));
}
// The look up and error-throwing method for mutable values.
template <class Key, class Value>
Value& GetMutableValueOrThrow(const Key& key,
std::unordered_map<Key, Value>* map) {
auto itr = map->find(key);
if (itr != map->end()) {
return itr->second;
}
throw std::logic_error(get_missing_id_message(key));
}
// Specializations for missing key based on key types.
template <>
std::string get_missing_id_message<SourceId>(const SourceId& key) {
std::stringstream ss;
ss << "Referenced geometry source " << key << " is not registered.";
return ss.str();
}
template <>
std::string get_missing_id_message<FrameId>(const FrameId& key) {
std::stringstream ss;
ss << "Referenced frame " << key << " has not been registered.";
return ss.str();
}
template <>
std::string get_missing_id_message<GeometryId>(const GeometryId& key) {
std::stringstream ss;
ss << "Referenced geometry " << key << " has not been registered.";
return ss.str();
}
//-----------------------------------------------------------------------------
template <typename T>
GeometryState<T>::GeometryState()
: self_source_(SourceId::get_new_id()),
geometry_engine_(make_unique<internal::ProximityEngine<T>>()) {
source_names_[self_source_] = "SceneGraphInternal";
const FrameId world = InternalFrame::world_frame_id();
// As an arbitrary design choice, we'll say the world frame is its own parent.
frames_[world] = InternalFrame(self_source_, world, "world",
InternalFrame::world_frame_group(),
0, world);
frame_index_to_id_map_.push_back(world);
kinematics_data_.X_WFs.push_back(RigidTransform<T>::Identity());
kinematics_data_.X_PFs.push_back(RigidTransform<T>::Identity());
source_frame_id_map_[self_source_] = {world};
source_deformable_geometry_id_map_[self_source_] = {};
source_frame_name_map_[self_source_] = {"world"};
source_root_frame_map_[self_source_] = {world};
}
namespace {
// Helper for the scalar-converting copy constructor.
// Copies the argument to use a different scalar type U => T.
// See #13618 and related for a possible generic replacement.
template <typename T, typename U>
static VectorX<T> ChangeScalarType(const VectorX<U>& other) {
if constexpr (std::is_same_v<T, U>) {
return other;
} else if constexpr (std::is_same_v<U, AutoDiffXd>) {
return math::DiscardZeroGradient(other);
} else {
return ExtractDoubleOrThrow(other);
}
}
// Helper for the scalar-converting copy constructor.
// Copies the argument to use a different scalar type U => T.
// See #13618 and related for a possible generic replacement.
template <typename T, typename U>
static RigidTransform<T> ChangeScalarType(const RigidTransform<U>& other) {
if constexpr (std::is_same_v<T, U>) {
return other;
} else if constexpr (std::is_same_v<U, AutoDiffXd>) {
return RigidTransform<T>(math::DiscardZeroGradient(other.GetAsMatrix34()));
} else {
return RigidTransform<T>(ExtractDoubleOrThrow(other.GetAsMatrix34()));
}
}
} // namespace
// It is _vitally_ important that all members are _explicitly_ accounted for
// (either in the initialization list or in the body). Failure to do so will
// lead to errors in the converted GeometryState instance.
template <typename T>
template <typename U>
GeometryState<T>::GeometryState(const GeometryState<U>& source)
: self_source_(source.self_source_),
source_frame_id_map_(source.source_frame_id_map_),
source_deformable_geometry_id_map_(
source.source_deformable_geometry_id_map_),
source_frame_name_map_(source.source_frame_name_map_),
source_root_frame_map_(source.source_root_frame_map_),
source_names_(source.source_names_),
source_anchored_geometry_map_(source.source_anchored_geometry_map_),
frames_(source.frames_),
geometries_(source.geometries_),
frame_index_to_id_map_(source.frame_index_to_id_map_),
geometry_engine_(
std::move(source.geometry_engine_->template ToScalarType<T>())),
render_engines_(source.render_engines_),
geometry_version_(source.geometry_version_) {
auto convert_pose_vector = [](const std::vector<RigidTransform<U>>& s,
std::vector<RigidTransform<T>>* d) {
std::vector<RigidTransform<T>>& dest = *d;
dest.resize(s.size());
for (size_t i = 0; i < s.size(); ++i) {
dest[i] = ChangeScalarType<T>(s[i]);
}
};
// TODO(xuchenhan-tri): The scalar conversion of KinematicsData should be
// handled by the KinematicsData class.
convert_pose_vector(source.kinematics_data_.X_PFs, &kinematics_data_.X_PFs);
convert_pose_vector(source.kinematics_data_.X_WFs, &kinematics_data_.X_WFs);
// Now convert the id -> pose map.
{
std::unordered_map<GeometryId, RigidTransform<T>>& dest =
kinematics_data_.X_WGs;
const std::unordered_map<GeometryId, RigidTransform<U>>& s =
source.kinematics_data_.X_WGs;
for (const auto& id_pose_pair : s) {
const GeometryId id = id_pose_pair.first;
const RigidTransform<U>& X_WG_source = id_pose_pair.second;
dest.insert({id, ChangeScalarType<T>(X_WG_source)});
}
}
// Now convert the id -> configuration map.
{
std::unordered_map<GeometryId, VectorX<T>>& dest = kinematics_data_.q_WGs;
const std::unordered_map<GeometryId, VectorX<U>>& s =
source.kinematics_data_.q_WGs;
for (const auto& id_configuration_pair : s) {
const GeometryId id = id_configuration_pair.first;
const VectorX<U>& q_WG_source = id_configuration_pair.second;
dest.insert({id, ChangeScalarType<T>(q_WG_source)});
}
}
}
template <typename T>
std::vector<GeometryId> GeometryState<T>::GetAllGeometryIds() const {
std::vector<GeometryId> ids;
ids.reserve(geometries_.size());
for (const auto& id_geometry_pair : geometries_) {
ids.push_back(id_geometry_pair.first);
}
std::sort(ids.begin(), ids.end());
return ids;
}
template <typename T>
unordered_set<GeometryId> GeometryState<T>::GetGeometryIds(
const GeometrySet& geometry_set, const std::optional<Role>& role) const {
return CollectIds(geometry_set, role);
}
template <typename T>
int GeometryState<T>::NumGeometriesWithRole(Role role) const {
int count = 0;
for (const auto& pair : geometries_) {
if (pair.second.has_role(role)) ++count;
}
return count;
}
template <typename T>
int GeometryState<T>::NumDynamicGeometries() const {
return NumDeformableGeometries() + NumDynamicNonDeformableGeometries();
}
template <typename T>
int GeometryState<T>::NumDynamicNonDeformableGeometries() const {
int count = 0;
for (const auto& pair : frames_) {
const InternalFrame& frame = pair.second;
if (frame.id() != InternalFrame::world_frame_id()) {
count += frame.num_child_geometries();
}
}
return count;
}
template <typename T>
int GeometryState<T>::NumDeformableGeometries() const {
int count = 0;
for (const auto& [source_id, deformable_geometry_ids] :
source_deformable_geometry_id_map_) {
unused(source_id);
count += deformable_geometry_ids.size();
}
return count;
}
template <typename T>
int GeometryState<T>::NumAnchoredGeometries() const {
const InternalFrame& frame = frames_.at(InternalFrame::world_frame_id());
int count = 0;
const std::unordered_set<GeometryId>& child_geometries =
frame.child_geometries();
for (auto geometry_id : child_geometries) {
if (!geometries_.at(geometry_id).is_deformable()) {
++count;
}
}
return count;
}
template <typename T>
std::set<std::pair<GeometryId, GeometryId>>
GeometryState<T>::GetCollisionCandidates() const {
std::set<std::pair<GeometryId, GeometryId>> pairs;
for (const auto& pairA : geometries_) {
const GeometryId idA = pairA.first;
const InternalGeometry& geometryA = pairA.second;
if (!geometryA.has_proximity_role()) continue;
for (const auto& pairB : geometries_) {
const GeometryId idB = pairB.first;
if (idB < idA) continue; // Only consider the pair (A, B) and not (B, A).
const InternalGeometry& geometryB = pairB.second;
if (!geometryB.has_proximity_role()) continue;
// This relies on CollisionFiltered() to handle if A == B, if they
// are both anchored, etc.
if (!CollisionFiltered(idA, idB)) {
pairs.insert({idA, idB});
}
}
}
return pairs;
}
template <typename T>
bool GeometryState<T>::SourceIsRegistered(SourceId source_id) const {
return source_frame_id_map_.find(source_id) != source_frame_id_map_.end();
}
template <typename T>
const std::string& GeometryState<T>::GetName(SourceId id) const {
auto itr = source_names_.find(id);
if (itr != source_names_.end()) return itr->second;
throw std::logic_error(
"Querying source name for an invalid source id: " + to_string(id) + ".");
}
template <typename T>
int GeometryState<T>::NumFramesForSource(SourceId source_id) const {
const auto& frame_set = GetValueOrThrow(source_id, source_frame_id_map_);
return static_cast<int>(frame_set.size());
}
template <typename T>
const FrameIdSet& GeometryState<T>::FramesForSource(
SourceId source_id) const {
return GetValueOrThrow(source_id, source_frame_id_map_);
}
template <typename T>
bool GeometryState<T>::BelongsToSource(FrameId frame_id,
SourceId source_id) const {
// Confirm that the source_id is valid; use the utility function to confirm
// source_id is valid and throw an exception with a known message.
GetValueOrThrow(source_id, source_frame_id_map_);
// If valid, test the frame.
return get_source_id(frame_id) == source_id;
}
template <typename T>
const std::string& GeometryState<T>::GetOwningSourceName(FrameId id) const {
SourceId source_id = get_source_id(id);
return source_names_.at(source_id);
}
template <typename T>
const std::string& GeometryState<T>::GetName(FrameId frame_id) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "No frame name available for invalid frame id: " +
to_string(frame_id);
});
return frames_.at(frame_id).name();
}
template <typename T>
FrameId GeometryState<T>::GetParentFrame(FrameId frame_id) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "No frame name available for invalid frame id: " +
to_string(frame_id);
});
const FrameId parent_frame_id = frames_.at(frame_id).parent_frame_id();
if (parent_frame_id == frame_id) {
// If there's no parent frame then world frame is implicitly the parent
return InternalFrame::world_frame_id();
}
return parent_frame_id;
}
template <typename T>
int GeometryState<T>::GetFrameGroup(FrameId frame_id) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "No frame group available for invalid frame id: " +
to_string(frame_id);
});
return frames_.at(frame_id).frame_group();
}
template <typename T>
int GeometryState<T>::NumGeometriesForFrame(FrameId frame_id) const {
const InternalFrame& frame = GetValueOrThrow(frame_id, frames_);
return static_cast<int>(frame.child_geometries().size());
}
template <typename T>
int GeometryState<T>::NumGeometriesForFrameWithRole(FrameId frame_id,
Role role) const {
const InternalFrame& frame = GetValueOrThrow(frame_id, frames_);
int count = 0;
for (GeometryId geometry_id : frame.child_geometries()) {
if (geometries_.at(geometry_id).has_role(role)) ++count;
}
return count;
}
template <typename T>
int GeometryState<T>::NumGeometriesWithRole(FrameId frame_id, Role role) const {
int count = 0;
FindOrThrow(frame_id, frames_, [frame_id, role]() {
return "Cannot report number of geometries with the " + to_string(role) +
" role for invalid frame id: " + to_string(frame_id);
});
const InternalFrame& frame = frames_.at(frame_id);
for (GeometryId id : frame.child_geometries()) {
if (geometries_.at(id).has_role(role)) ++count;
}
return count;
}
template <typename T>
std::vector<GeometryId> GeometryState<T>::GetGeometries(
FrameId frame_id, std::optional<Role> role) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return fmt::format(
"Cannot report geometries associated with invalid frame id: {}",
frame_id);
});
const InternalFrame& frame = frames_.at(frame_id);
std::vector<GeometryId> ids;
ids.reserve(frame.child_geometries().size());
for (GeometryId g_id : frame.child_geometries()) {
if (role.has_value()) {
if (!geometries_.at(g_id).has_role(*role)) continue;
}
ids.push_back(g_id);
}
std::sort(ids.begin(), ids.end());
return ids;
}
template <typename T>
GeometryId GeometryState<T>::GetGeometryIdByName(
FrameId frame_id, Role role, const std::string& name) const {
const std::string canonical_name = internal::CanonicalizeStringName(name);
GeometryId result;
int count = 0;
std::string frame_name;
const InternalFrame& frame = GetValueOrThrow(frame_id, frames_);
frame_name = frame.name();
for (GeometryId geometry_id : frame.child_geometries()) {
const InternalGeometry& geometry = geometries_.at(geometry_id);
if (geometry.has_role(role) && geometry.name() == canonical_name) {
++count;
result = geometry_id;
}
}
if (count == 1) return result;
if (count < 1) {
throw std::logic_error("The frame '" + frame_name + "' (" +
to_string(frame_id) + ") has no geometry with the role '" +
to_string(role) + "' and the canonical name '" + canonical_name + "'");
}
// This case should only be possible for unassigned geometries - internal
// invariants require unique names for actual geometries with the _same_
// role on the same frame.
DRAKE_DEMAND(role == Role::kUnassigned);
throw std::logic_error("The frame '" + frame_name + "' (" +
to_string(frame_id) + ") has multiple geometries with the role '" +
to_string(role) + "' and the canonical name '" + canonical_name + "'");
}
template <typename T>
bool GeometryState<T>::BelongsToSource(GeometryId geometry_id,
SourceId source_id) const {
// Confirm valid source id.
FindOrThrow(source_id, source_names_, [source_id](){
return get_missing_id_message(source_id);
});
// If this fails, the geometry_id is not valid and an exception is thrown.
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
return geometry.belongs_to_source(source_id);
}
template <typename T>
const std::string& GeometryState<T>::GetOwningSourceName(GeometryId id) const {
SourceId source_id = get_source_id(id);
return source_names_.at(source_id);
}
template <typename T>
FrameId GeometryState<T>::GetFrameId(GeometryId geometry_id) const {
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
return geometry.frame_id();
}
template <typename T>
const std::string& GeometryState<T>::GetName(GeometryId geometry_id) const {
const InternalGeometry* geometry = GetGeometry(geometry_id);
if (geometry != nullptr) return geometry->name();
throw std::logic_error("No geometry available for invalid geometry id: " +
to_string(geometry_id));
}
template <typename T>
const Shape& GeometryState<T>::GetShape(GeometryId id) const {
const InternalGeometry* geometry = GetGeometry(id);
if (geometry != nullptr) return geometry->shape();
throw std::logic_error("No geometry available for invalid geometry id: " +
to_string(id));
}
template <typename T>
const math::RigidTransform<double>& GeometryState<T>::GetPoseInFrame(
GeometryId geometry_id) const {
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
return geometry.X_FG();
}
template <typename T>
const math::RigidTransform<double>& GeometryState<T>::GetPoseInParent(
GeometryId geometry_id) const {
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
return geometry.X_PG();
}
template <typename T>
std::variant<std::monostate, const TriangleSurfaceMesh<double>*,
const VolumeMesh<double>*>
GeometryState<T>::maybe_get_hydroelastic_mesh(GeometryId geometry_id) const {
const auto& hydro_geometries = geometry_engine_->hydroelastic_geometries();
switch (hydro_geometries.hydroelastic_type(geometry_id)) {
case HydroelasticType::kUndefined:
break;
case HydroelasticType::kRigid: {
const auto& rigid = hydro_geometries.rigid_geometry(geometry_id);
if (!rigid.is_half_space()) {
return &rigid.mesh();
}
break;
}
case HydroelasticType::kSoft: {
const auto& soft = hydro_geometries.soft_geometry(geometry_id);
if (!soft.is_half_space()) {
return &soft.mesh();
}
break;
}
}
return {};
}
template <typename T>
const ProximityProperties* GeometryState<T>::GetProximityProperties(
GeometryId id) const {
const InternalGeometry* geometry = GetGeometry(id);
if (geometry) return geometry->proximity_properties();
throw std::logic_error(
fmt::format("Referenced geometry {} has not been registered", id));
}
template <typename T>
const IllustrationProperties* GeometryState<T>::GetIllustrationProperties(
GeometryId id) const {
const InternalGeometry* geometry = GetGeometry(id);
if (geometry) return geometry->illustration_properties();
throw std::logic_error(
fmt::format("Referenced geometry {} has not been registered", id));
}
template <typename T>
const PerceptionProperties* GeometryState<T>::GetPerceptionProperties(
GeometryId id) const {
const InternalGeometry* geometry = GetGeometry(id);
if (geometry) return geometry->perception_properties();
throw std::logic_error(
fmt::format("Referenced geometry {} has not been registered", id));
}
template <typename T>
const VolumeMesh<double>* GeometryState<T>::GetReferenceMesh(
GeometryId id) const {
const InternalGeometry* geometry = GetGeometry(id);
if (geometry == nullptr) {
throw std::logic_error(
fmt::format("Referenced geometry {} has not been registered", id));
}
return geometry->reference_mesh();
}
template <typename T>
bool GeometryState<T>::IsDeformableGeometry(GeometryId id) const {
const InternalGeometry& geometry = GetValueOrThrow(id, geometries_);
return geometry.is_deformable();
}
template <typename T>
std::vector<GeometryId> GeometryState<T>::GetAllDeformableGeometryIds() const {
std::vector<GeometryId> ids;
for (const auto& it : source_deformable_geometry_id_map_) {
ids.insert(ids.end(), it.second.begin(), it.second.end());
}
std::sort(ids.begin(), ids.end());
return ids;
}
template <typename T>
bool GeometryState<T>::CollisionFiltered(GeometryId id1, GeometryId id2) const {
std::string base_message =
"Can't report collision filter status between geometries " +
to_string(id1) + " and " + to_string(id2) + "; ";
const internal::InternalGeometry* geometry1 = GetGeometry(id1);
const internal::InternalGeometry* geometry2 = GetGeometry(id2);
if (geometry1 != nullptr && geometry2 != nullptr) {
if (geometry1->has_proximity_role() && geometry2->has_proximity_role()) {
return !geometry_engine_->collision_filter().CanCollideWith(
geometry1->id(), geometry2->id());
}
if (geometry1->has_proximity_role()) {
throw std::logic_error(base_message + to_string(id2) +
" does not have a proximity role");
} else if (geometry2->has_proximity_role()) {
throw std::logic_error(base_message + to_string(id1) +
" does not have a proximity role");
} else {
throw std::logic_error(base_message + " neither id has a proximity role");
}
}
if (geometry1 != nullptr) {
throw std::logic_error(base_message + to_string(id2) +
" is not a valid geometry");
} else if (geometry2 != nullptr) {
throw std::logic_error(base_message + to_string(id1) +
" is not a valid geometry");
} else {
throw std::logic_error(base_message + "neither id is a valid geometry");
}
}
template <typename T>
const math::RigidTransform<T>& GeometryState<T>::get_pose_in_world(
FrameId frame_id) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "No world pose available for invalid frame id: " +
to_string(frame_id);
});
return kinematics_data_.X_WFs[frames_.at(frame_id).index()];
}
template <typename T>
const math::RigidTransform<T>& GeometryState<T>::get_pose_in_world(
GeometryId geometry_id) const {
FindOrThrow(geometry_id, geometries_, [geometry_id]() {
return "No world pose available for invalid geometry id: " +
to_string(geometry_id);
});
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
if (geometry.is_deformable()) {
throw std::logic_error(
"Deformable geometries are characterized by vertex positions. Use "
"get_configurations_in_world() instead.");
}
return kinematics_data_.X_WGs.at(geometry_id);
}
template <typename T>
const math::RigidTransform<T>& GeometryState<T>::get_pose_in_parent(
FrameId frame_id) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "No pose available for invalid frame id: " + to_string(frame_id);
});
return kinematics_data_.X_PFs[frames_.at(frame_id).index()];
}
template <typename T>
const VectorX<T>& GeometryState<T>::get_configurations_in_world(
GeometryId geometry_id) const {
FindOrThrow(geometry_id, geometries_, [geometry_id]() {
return "No world configurations available for invalid geometry id: " +
to_string(geometry_id);
});
const auto& geometry = GetValueOrThrow(geometry_id, geometries_);
if (!geometry.is_deformable()) {
throw std::logic_error(
"Non-deformable geometries are characterized by poses. Use "
"get_pose_in_world() instead.");
}
return kinematics_data_.q_WGs.at(geometry_id);
}
template <typename T>
SourceId GeometryState<T>::RegisterNewSource(const std::string& name) {
SourceId source_id = SourceId::get_new_id();
const std::string final_name =
name != "" ? name : "Source_" + to_string(source_id);
// The user can provide bad names, _always_ test.
for (const auto& pair : source_names_) {
if (pair.second == final_name) {
throw std::logic_error(
"Registering new source with duplicate name: " + final_name + ".");
}
}
source_frame_id_map_[source_id];
source_deformable_geometry_id_map_[source_id];
source_frame_name_map_[source_id];
source_root_frame_map_[source_id];
source_anchored_geometry_map_[source_id];
source_names_[source_id] = final_name;
return source_id;
}
template <typename T>
FrameId GeometryState<T>::RegisterFrame(SourceId source_id,
const GeometryFrame& frame) {
return RegisterFrame(source_id, InternalFrame::world_frame_id(), frame);
}
template <typename T>
FrameId GeometryState<T>::RegisterFrame(SourceId source_id, FrameId parent_id,
const GeometryFrame& frame) {
FrameId frame_id = frame.id();
if (frames_.count(frame_id) > 0) {
throw std::logic_error(
"Registering frame with an id that has already been registered: " +
to_string(frame_id));
}
FrameIdSet& f_set = GetMutableValueOrThrow(source_id, &source_frame_id_map_);
if (parent_id != InternalFrame::world_frame_id()) {
FindOrThrow(parent_id, f_set, [parent_id, source_id]() {
return "Indicated parent id " + to_string(parent_id) + " does not belong "
"to the indicated source id " + to_string(source_id) + ".";
});
frames_[parent_id].add_child(frame_id);
} else {
// The parent is the world frame; register it as a root frame.
source_root_frame_map_[source_id].insert(frame_id);
}
FrameNameSet& f_name_set = source_frame_name_map_[source_id];
const auto& [iterator, was_inserted] = f_name_set.insert(frame.name());
if (!was_inserted) {
throw std::logic_error(
fmt::format("Registering frame for source '{}'"
" with a duplicate name '{}'",
source_names_[source_id], frame.name()));
}
DRAKE_ASSERT(kinematics_data_.X_PFs.size() == frame_index_to_id_map_.size());
int index(static_cast<int>(kinematics_data_.X_PFs.size()));
kinematics_data_.X_PFs.emplace_back(RigidTransform<T>::Identity());
kinematics_data_.X_WFs.emplace_back(RigidTransform<T>::Identity());
frame_index_to_id_map_.push_back(frame_id);
f_set.insert(frame_id);
frames_.emplace(frame_id, InternalFrame(source_id, frame_id, frame.name(),
frame.frame_group(), index,
parent_id));
return frame_id;
}
template <typename T>
GeometryId GeometryState<T>::RegisterGeometry(
SourceId source_id, FrameId frame_id,
std::unique_ptr<GeometryInstance> geometry) {
if (geometry == nullptr) {
throw std::logic_error(
"Registering null geometry to frame " + to_string(frame_id) +
", on source " + to_string(source_id) + ".");
}
const GeometryId geometry_id = geometry->id();
ValidateRegistrationAndSetTopology(source_id, frame_id, geometry_id);
// pose() is always RigidTransform<double>. To account for
// GeometryState<AutoDiff>, we need to cast it to the common type T.
const InternalFrame& frame = frames_[frame_id];
kinematics_data_.X_WGs[geometry_id] =
kinematics_data_.X_WFs[frame.index()] * geometry->pose().cast<T>();
geometries_.emplace(
geometry_id,
InternalGeometry(source_id, geometry->release_shape(), frame_id,
geometry_id, geometry->name(), geometry->pose()));
AssignAllDefinedRoles(source_id, std::move(geometry));
return geometry_id;
}
template <typename T>
GeometryId GeometryState<T>::RegisterDeformableGeometry(
SourceId source_id, FrameId frame_id,
std::unique_ptr<GeometryInstance> geometry, double resolution_hint) {
if (geometry == nullptr) {
throw std::logic_error("Registering null geometry to frame " +
to_string(frame_id) + ", on source " +
to_string(source_id) + ".");
}
const GeometryId geometry_id = geometry->id();
if (frame_id != InternalFrame::world_frame_id()) {
throw std::logic_error("Registering deformable geometry with id " +
to_string(geometry_id) + " to a non-world frame");
}
ValidateRegistrationAndSetTopology(source_id, frame_id, geometry_id);
source_deformable_geometry_id_map_[source_id].insert(geometry_id);
InternalGeometry internal_geometry(source_id, geometry->release_shape(),
frame_id, geometry_id, geometry->name(),
geometry->pose(), resolution_hint);
// The reference mesh is defined in the frame F.
const VolumeMesh<double>* reference_mesh = internal_geometry.reference_mesh();
DRAKE_DEMAND(reference_mesh != nullptr);
const InternalFrame& frame = frames_[frame_id];
const RigidTransform<T> X_WG =
kinematics_data_.X_WFs[frame.index()] * geometry->pose().cast<T>();
VectorX<T> q_WG(reference_mesh->num_vertices() * 3);
for (int v = 0; v < reference_mesh->num_vertices(); ++v) {
q_WG.template segment<3>(3 * v) =
X_WG * Vector3<T>(reference_mesh->vertex(v));
}
kinematics_data_.q_WGs[geometry_id] = std::move(q_WG);
geometries_.emplace(geometry_id, std::move(internal_geometry));
AssignAllDefinedRoles(source_id, std::move(geometry));
return geometry_id;
}
template <typename T>
void GeometryState<T>::ChangeShape(SourceId source_id, GeometryId geometry_id,
const Shape& shape,
std::optional<RigidTransformd> X_FG) {
if (!BelongsToSource(geometry_id, source_id)) {
throw std::logic_error("Given geometry id " + to_string(geometry_id) +
" does not belong to the given source id " +
to_string(source_id));
}
InternalGeometry* geometry = GetMutableGeometry(geometry_id);
// Must be non-null, otherwise, we never would've gotten past the
// `BelongsToSource()` call.
DRAKE_DEMAND(geometry != nullptr);
// TODO(SeanCurtis-TRI) Allow changing deformable geometries after the fact;
// this would require coordination with MbP because the state of the
// deformable object must be consistent between the two systems; the size of
// the data in the corresponding port would have to change on both sides.
if (geometry->is_deformable()) {
throw std::logic_error(
"Cannot use ChangeShape() to change the shape of deformable "
"geometries.");
}
geometry->SetShape(shape);
if (X_FG.has_value()) {
// As documented on SceneGraph::SetShape(); use the old pose unless
// explicitly changed.
geometry->set_pose(*X_FG);
}
// We've changed pose and shape; now we just need to notify the various
// engines to update themselves.
if (geometry->has_proximity_role()) {
// Proximity engine is best handled by removal and re-addition; we use the
// unchecked version because we just need the engine mechanism; no
// further GeometryState checking.
RemoveFromProximityEngineUnchecked(*geometry);
AddToProximityEngineUnchecked(*geometry);
}
if (geometry->has_illustration_role()) {
// Illustration has no "engine"; it's just the InternalGeometry. All
// reifications of illustration geometry happen outside of SceneGraph. We
// just need to let them know that the work is necessary.
geometry_version_.modify_illustration();
}
if (geometry->has_perception_role()) {
// Render engines are best handled by removal and re-addition; we use the
// unchecked version because we just need the engine mechanism; no
// further GeometryState checking.
RemoveFromAllRenderersUnchecked(geometry_id);
AddToCompatibleRenderersUnchecked(*geometry);
}
}
template <typename T>
GeometryId GeometryState<T>::RegisterGeometryWithParent(
SourceId source_id, GeometryId parent_id,
std::unique_ptr<GeometryInstance> geometry) {
// There are three error conditions in the doxygen:
// 1. geometry == nullptr,
// 2. source_id is not a registered source, and
// 3. parent_id doesn't belong to source_id.
//
// Only #1 is tested directly. #2 and #3 are tested implicitly during the act
// of registering the geometry.
if (geometry == nullptr) {
throw std::logic_error(
"Registering null geometry to geometry " + to_string(parent_id) +
", on source " + to_string(source_id) + ".");
}
// This confirms that parent_id exists at all.
InternalGeometry& parent_geometry =
GetMutableValueOrThrow(parent_id, &geometries_);
FrameId frame_id = parent_geometry.frame_id();
// This implicitly confirms that source_id is registered (condition #2) and
// that frame_id belongs to source_id. By construction, parent_id must
// belong to the same source as frame_id, so this tests condition #3.
GeometryId new_id = RegisterGeometry(source_id, frame_id, move(geometry));
// RegisterGeometry stores X_PG into X_FG_ (having assumed that the
// parent was a frame). This replaces the stored X_PG value with the
// semantically correct value X_FG by concatenating X_FP with X_PG.
// Transform pose relative to geometry, to pose relative to frame.
InternalGeometry& new_geometry = geometries_[new_id];
// The call to `RegisterGeometry()` above stashed the pose X_PG into the
// X_FG_ vector assuming the parent was the frame. Replace it by concatenating
// its pose in parent, with its parent's pose in frame. NOTE: the pose is no
// longer available from geometry because of the `move(geometry)`.
const RigidTransform<double>& X_PG = new_geometry.X_FG();
const RigidTransform<double>& X_FP = parent_geometry.X_FG();
new_geometry.set_geometry_parent(parent_id, X_FP * X_PG);
parent_geometry.add_child(new_id);
return new_id;
}
template <typename T>
GeometryId GeometryState<T>::RegisterAnchoredGeometry(
SourceId source_id,
std::unique_ptr<GeometryInstance> geometry) {
return RegisterGeometry(source_id, InternalFrame::world_frame_id(),
std::move(geometry));
}
template <typename T>
void GeometryState<T>::RemoveGeometry(SourceId source_id,
GeometryId geometry_id) {
if (!BelongsToSource(geometry_id, source_id)) {
throw std::logic_error(
"Trying to remove geometry " + to_string(geometry_id) + " from "
"source " + to_string(source_id) + ", but the geometry doesn't "
"belong to that source.");
}
RemoveGeometryUnchecked(geometry_id, RemoveGeometryOrigin::kGeometry);
}
template <typename T>
bool GeometryState<T>::IsValidGeometryName(
FrameId frame_id, Role role, const std::string& candidate_name) const {
FindOrThrow(frame_id, frames_, [frame_id]() {
return "Given frame id is not valid: " + to_string(frame_id);
});
const std::string name = internal::CanonicalizeStringName(candidate_name);
if (name.empty()) return false;
return NameIsUnique(frame_id, role, name);
}
template <typename T>
void GeometryState<T>::AssignRole(SourceId source_id, GeometryId geometry_id,
ProximityProperties properties,
RoleAssign assign) {
InternalGeometry& geometry =
ValidateRoleAssign(source_id, geometry_id, Role::kProximity, assign);
geometry_version_.modify_proximity();
switch (assign) {
case RoleAssign::kNew: {
geometry.SetRole(std::move(properties));
if (geometry.is_deformable()) {
DRAKE_DEMAND(geometry.reference_mesh() != nullptr);
geometry_engine_->AddDeformableGeometry(*geometry.reference_mesh(),
geometry_id);
} else if (geometry.is_dynamic()) {
// Pass the geometry to the engine.
const RigidTransformd& X_WG =
convert_to_double(kinematics_data_.X_WGs.at(geometry_id));
geometry_engine_->AddDynamicGeometry(geometry.shape(), X_WG,
geometry_id,
*geometry.proximity_properties());
} else {
geometry_engine_->AddAnchoredGeometry(geometry.shape(), geometry.X_FG(),
geometry_id,
*geometry.proximity_properties());
}
// The set of geometries G such that I need to introduce filtered pairs