-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathspanning_forest_test.cc
2038 lines (1737 loc) · 90.4 KB
/
spanning_forest_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
/* clang-format off to disable clang-format-includes */
#include "drake/multibody/topology/forest.h"
/* clang-format on */
#include <string>
#include <tuple>
#include <fmt/format.h>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include "drake/common/test_utilities/expect_throws_message.h"
// Tests here are those that require definition of SpanningForest, including
// tests of LinkJointGraph interactions with its SpanningForest. See
// link_joint_graph_test.cc for tests that need only LinkJointGraph
// definitions.
namespace drake {
namespace multibody {
namespace internal {
using std::pair;
namespace {
// A default-constructed LinkJointGraph contains a predefined World
// Link, and can generate a valid SpanningForest containing just a World
// Mobod. The LinkJointGraph should be properly updated to have
// a single LinkComposite and proper modeling info.
GTEST_TEST(SpanningForest, WorldOnlyTest) {
LinkJointGraph graph;
const SpanningForest& forest = graph.forest();
// Check that the internal forest is wired correctly but not valid yet.
EXPECT_EQ(&forest.graph(), &graph);
EXPECT_FALSE(graph.forest_is_valid());
EXPECT_FALSE(forest.is_valid());
EXPECT_EQ(forest.height(), 0);
EXPECT_TRUE(forest.mobods().empty());
EXPECT_TRUE(forest.trees().empty());
EXPECT_TRUE(forest.loop_constraints().empty());
// The default-constructed graph should contain only World.
EXPECT_EQ(ssize(graph.links()), 1);
EXPECT_TRUE(graph.joints().empty());
EXPECT_EQ(graph.world_link().name(), "world");
EXPECT_EQ(graph.world_link().model_instance(), world_model_instance());
const BodyIndex world_link_index = graph.world_link().index();
EXPECT_EQ(world_link_index, BodyIndex(0));
const LinkOrdinal world_link_ordinal = graph.world_link().ordinal();
EXPECT_EQ(world_link_ordinal, LinkOrdinal(0));
// Now build a forest representing the World-only graph.
EXPECT_TRUE(graph.BuildForest());
EXPECT_TRUE(graph.forest_is_valid());
EXPECT_TRUE(forest.is_valid());
EXPECT_EQ(&forest.graph(), &graph);
const SpanningForest::Mobod& world = forest.mobods(MobodIndex(0));
EXPECT_EQ(&world, &forest.world_mobod());
const MobodIndex world_mobod_index = forest.world_mobod().index();
EXPECT_EQ(world_mobod_index, MobodIndex(0));
EXPECT_EQ(graph.link_to_mobod(world_link_index), MobodIndex(0));
EXPECT_EQ(ssize(graph.link_composites()), 1);
EXPECT_EQ(ssize(graph.link_composites(LinkCompositeIndex(0)).links), 1);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links[0],
world_link_index);
// Check that the World-only forest makes sense.
EXPECT_EQ(ssize(forest.mobods()), 1);
EXPECT_TRUE(forest.trees().empty()); // World isn't part of a tree.
EXPECT_TRUE(forest.loop_constraints().empty());
EXPECT_EQ(forest.height(), 1);
EXPECT_EQ(ssize(forest.welded_mobods()), 1);
EXPECT_EQ(forest.welded_mobods()[0][0], world_mobod_index);
EXPECT_EQ(forest.mobod_to_link_ordinal(world_mobod_index),
world_link_ordinal);
EXPECT_EQ(ssize(forest.mobod_to_link_ordinals(world_mobod_index)), 1);
EXPECT_EQ(forest.mobod_to_link_ordinals(world_mobod_index)[0],
world_link_ordinal);
EXPECT_EQ(forest.num_positions(), 0);
EXPECT_EQ(forest.num_velocities(), 0);
EXPECT_TRUE(forest.quaternion_starts().empty());
// Exercise the Mobod API to check the World Mobod for reasonableness.
EXPECT_TRUE(world.is_world());
EXPECT_FALSE(world.is_base_body());
EXPECT_TRUE(world.is_anchored());
EXPECT_TRUE(world.is_leaf_mobod());
EXPECT_FALSE(world.is_reversed()); // Not meaningful though.
EXPECT_TRUE(world.is_weld()); // Defined as having no inboard dofs.
EXPECT_FALSE(world.inboard().is_valid());
EXPECT_TRUE(world.outboards().empty());
EXPECT_EQ(world.link_ordinal(), world_link_ordinal);
EXPECT_EQ(ssize(world.follower_link_ordinals()), 1);
EXPECT_EQ(world.follower_link_ordinals()[0], world_link_ordinal);
EXPECT_FALSE(world.joint_ordinal().is_valid());
EXPECT_FALSE(world.tree().is_valid());
EXPECT_EQ(world.welded_mobods_group(), WeldedMobodsIndex(0));
EXPECT_EQ(world.level(), 0);
EXPECT_EQ(world.q_start(), 0);
EXPECT_EQ(world.nq(), 0);
EXPECT_EQ(world.v_start(), 0);
EXPECT_EQ(world.nv(), 0);
EXPECT_EQ(world.nq_inboard(), 0);
EXPECT_EQ(world.nv_inboard(), 0);
EXPECT_EQ(world.nq_outboard(), 0);
EXPECT_EQ(world.nv_outboard(), 0);
EXPECT_FALSE(world.has_quaternion());
EXPECT_EQ(world.num_subtree_mobods(), 1);
EXPECT_EQ(world.subtree_velocities(), (std::pair{0, 0}));
EXPECT_EQ(world.outboard_velocities(), (std::pair{0, 0}));
// Check that if we clear the graph, the forest returns to its invalid
// condition as above.
graph.Clear();
EXPECT_EQ(&forest.graph(), &graph); // Still wired right.
EXPECT_FALSE(graph.forest_is_valid());
EXPECT_FALSE(forest.is_valid());
EXPECT_EQ(forest.height(), 0);
EXPECT_TRUE(forest.mobods().empty());
EXPECT_TRUE(forest.trees().empty());
EXPECT_TRUE(forest.loop_constraints().empty());
}
GTEST_TEST(SpanningForest, TreeAndLoopConstraintAPIs) {
LinkJointGraph graph;
const SpanningForest& forest = graph.forest();
EXPECT_TRUE(graph.BuildForest());
// This stub exists solely to enable these API tests until the implementing
// code is merged. Here's the forest we're expecting:
// -> mobod1 => mobod2
// World ^
// -> mobod3 .....| loop constraint
// There are two 1-dof "->" joints and one 0-dof "=>" weld.
// TODO(sherm1) Make the same forest legitimately.
const_cast<SpanningForest&>(forest).AddStubTreeAndLoopConstraint();
EXPECT_EQ(ssize(forest.trees()), 2);
EXPECT_EQ(ssize(forest.mobods()), 4);
EXPECT_EQ(ssize(forest.loop_constraints()), 1);
// Not much to check for the loop constraint.
const auto& loop_constraint = forest.loop_constraints(LoopConstraintIndex(0));
EXPECT_EQ(loop_constraint.index(), LoopConstraintIndex(0));
EXPECT_EQ(loop_constraint.primary_mobod(), MobodIndex(3));
EXPECT_EQ(loop_constraint.shadow_mobod(), MobodIndex(2));
const SpanningForest::Tree& tree0 = forest.trees(TreeIndex(0));
EXPECT_EQ(tree0.index(), TreeIndex(0));
EXPECT_EQ(tree0.height(), 2);
EXPECT_EQ(tree0.base_mobod(), MobodIndex(1));
EXPECT_EQ(tree0.last_mobod(), MobodIndex(2));
EXPECT_EQ(tree0.begin()->index(), MobodIndex(1));
EXPECT_EQ(tree0.end() - tree0.begin(), 2);
EXPECT_EQ(tree0.front().index(), MobodIndex(1));
EXPECT_EQ(tree0.back().index(), MobodIndex(2));
EXPECT_EQ(tree0.num_mobods(), 2);
EXPECT_EQ(tree0.q_start(), 0);
EXPECT_EQ(tree0.v_start(), 0);
EXPECT_EQ(tree0.nq(), 1);
EXPECT_EQ(tree0.nv(), 1);
const SpanningForest::Tree& tree1 = forest.trees(TreeIndex(1));
EXPECT_EQ(tree1.index(), TreeIndex(1));
EXPECT_EQ(tree1.height(), 1);
EXPECT_EQ(tree1.base_mobod(), MobodIndex(3));
EXPECT_EQ(tree1.last_mobod(), MobodIndex(3));
EXPECT_EQ(tree1.begin()->index(), MobodIndex(3));
EXPECT_EQ(tree1.end() - tree1.begin(), 1);
EXPECT_EQ(tree1.front().index(), MobodIndex(3));
EXPECT_EQ(tree1.back().index(), MobodIndex(3));
EXPECT_EQ(tree1.num_mobods(), 1);
EXPECT_EQ(tree1.q_start(), 1);
EXPECT_EQ(tree1.v_start(), 1);
EXPECT_EQ(tree1.nq(), 1);
EXPECT_EQ(tree1.nv(), 1);
}
/* Creates a straightforward graph of two trees each with multiple branches,
plus a lone unattached free link. There are no welds or reverse joints or loops.
We intentionally jumble the link numbering to make sure we don't get the right
forest numbering by luck. We'll use this to test that basic numbering and
reporting works. We'll reuse this in several tests with different options.
Here is the original graph and its expected forest model:
Links Mobods
15 13
13 14 11 12
9 10 11 5 6 10
5 6 8 7 --> 3 4 9 14
4 3 2 8
1 2 12 1 7 15
..........0.......... ...........0..........
Note the depth-first ordering in the Forest. We won't provide joints to World
but the modeler's base body policy should choose Links 1, 2, and 12 and add
appropriate joints. Also note our policy of moving all singleton free
links to the highest-numbered mobods.
Note also that the left link tree maps to forest tree0, the right link tree
maps to forest tree1, and the free link is forest tree2. */
LinkJointGraph MakeMultiBranchGraph(ModelInstanceIndex left,
ModelInstanceIndex right,
ModelInstanceIndex free_link) {
LinkJointGraph graph;
graph.RegisterJointType("revolute", 1, 1);
// Map links to their model instances.
std::map<int, ModelInstanceIndex> link_to_instance{
{1, left}, {4, left}, {5, left}, {6, left},
{9, left}, {10, left}, //
{2, free_link}, //
{12, right}, {3, right}, {8, right}, {7, right},
{11, right}, {13, right}, {14, right}, {15, right}};
// Define the graph. Links:
for (int i = 1; i <= 15; ++i)
graph.AddLink("link" + std::to_string(i), link_to_instance[i]);
// Joints: (Check against left-hand diagram above.)
const std::vector<std::pair<int, int>> joints{
{1, 4}, {4, 5}, {4, 6}, {6, 9}, {6, 10}, // left
{12, 3}, {3, 8}, {3, 7}, {8, 11}, {11, 13}, {11, 14}, {14, 15}}; // right
for (int i = 0; i < ssize(joints); ++i) {
const auto joint = joints[i];
graph.AddJoint("joint" + std::to_string(i), link_to_instance[joint.second],
"revolute", BodyIndex(joint.first), BodyIndex(joint.second));
}
// Remove and re-add a joint to mess up the numbering. It will now have
// JointIndex 12, and 7 should be unused.
EXPECT_TRUE(graph.has_joint(JointIndex(7)));
EXPECT_TRUE(graph.HasJointNamed("joint7", link_to_instance[7]));
graph.RemoveJoint(JointIndex(7)); // The joint between 3 & 8.
graph.AddJoint("joint7replaced", link_to_instance[7], "revolute",
BodyIndex(3), BodyIndex(7));
EXPECT_FALSE(graph.has_joint(JointIndex(7)));
EXPECT_FALSE(graph.HasJointNamed("joint7", link_to_instance[7]));
EXPECT_TRUE(graph.has_joint(JointIndex(12)));
EXPECT_TRUE(graph.HasJointNamed("joint7replaced", link_to_instance[7]));
// Make sure we got the graph we're expecting. Before building the forest
// the only links and joints are the user-added ones.
EXPECT_EQ(ssize(graph.links()), 16); // includes World
EXPECT_EQ(ssize(graph.joints()), 12);
EXPECT_EQ(graph.num_user_links(), 16);
EXPECT_EQ(graph.num_user_joints(), 12);
return graph;
}
/* Build the above graph with default options and then dig into the result
in detail to make sure all the relevant APIs work. Also verify base link
choice policy, and free link placement at the end. */
GTEST_TEST(SpanningForest, MultipleBranchesDefaultOptions) {
const ModelInstanceIndex left_instance(5), right_instance(6),
free_link_instance(7); // arbitrary
LinkJointGraph graph =
MakeMultiBranchGraph(left_instance, right_instance, free_link_instance);
const SpanningForest& forest = graph.forest();
// Some basic sanity checks for the forest object.
EXPECT_EQ(&forest.graph(), &graph); // check backpointer
EXPECT_EQ(&forest.links(), &graph.links());
EXPECT_EQ(&forest.joints(), &graph.joints());
// Build with default options.
EXPECT_TRUE(graph.BuildForest());
EXPECT_EQ(forest.options(), ForestBuildingOptions::kDefault);
EXPECT_EQ(forest.options(left_instance), ForestBuildingOptions::kDefault);
EXPECT_EQ(forest.options(right_instance), ForestBuildingOptions::kDefault);
EXPECT_EQ(forest.options(free_link_instance),
ForestBuildingOptions::kDefault);
// See that the graph got augmented properly to reflect the as-built forest.
EXPECT_EQ(graph.num_user_links(), 16);
EXPECT_EQ(ssize(graph.links()), 16); // no links added
EXPECT_EQ(graph.num_user_joints(), 12);
EXPECT_EQ(ssize(graph.joints()), 15); // modeling adds 3 floating joints
// The only LinkComposite is the World composite and it is alone there.
EXPECT_EQ(ssize(graph.link_composites()), 1); // just World
EXPECT_EQ(ssize(graph.link_composites(LinkCompositeIndex(0)).links), 1);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links[0],
graph.world_link().index());
EXPECT_EQ(ssize(forest.trees()), 3);
EXPECT_EQ(ssize(forest.mobods()), 16); // includes World
EXPECT_EQ(ssize(forest.welded_mobods()), 1); // just World
EXPECT_EQ(forest.num_positions(), 33); // 12 revolute, 3 x 7 quat floating
EXPECT_EQ(forest.num_velocities(), 30); // 12 revolute, 3 x 6 floating
// Verify that we're tracking quaternions properly.
EXPECT_EQ(ssize(forest.quaternion_starts()), 3); // One per floating joint.
EXPECT_EQ(forest.quaternion_starts(), (std::vector{0, 12, 26}));
EXPECT_FALSE(forest.mobods(MobodIndex(10)).has_quaternion()); // Arbitrary.
EXPECT_TRUE(forest.mobods(MobodIndex(1)).has_quaternion());
EXPECT_TRUE(forest.mobods(MobodIndex(7)).has_quaternion());
EXPECT_TRUE(forest.mobods(MobodIndex(15)).has_quaternion());
// Check Mobod->Link and Link->Mobod mappings.
const std::vector<pair<int, int>> mobod_link_map{
{0, 0}, {1, 1}, {2, 4}, {3, 5}, {4, 6}, {5, 9}, {6, 10}, {7, 12},
{8, 3}, {9, 8}, {10, 11}, {11, 13}, {12, 14}, {13, 15}, {14, 7}, {15, 2}};
for (auto mobod_link : mobod_link_map) {
EXPECT_EQ(graph.link_to_mobod(BodyIndex(mobod_link.second)),
MobodIndex(mobod_link.first));
EXPECT_EQ(forest.mobod_to_link_ordinal(MobodIndex(mobod_link.first)),
LinkOrdinal(mobod_link.second));
// Each Mobod has only a single Link that follows it.
EXPECT_EQ(
ssize(forest.mobod_to_link_ordinals(MobodIndex(mobod_link.first))), 1);
EXPECT_EQ(forest.mobod_to_link_ordinals(MobodIndex(mobod_link.first))[0],
LinkOrdinal(mobod_link.second));
}
EXPECT_EQ(forest.height(), 7);
// Check that the three Trees in the forest make sense.
// Reminder: left->tree0, right->tree1, free link->tree2.
auto tree_check = [&forest](int index, int height, int base_mobod,
int last_mobod, int num_mobods, int q_start,
int nq, int v_start, int nv) {
const SpanningForest::Tree& tree = forest.trees(TreeIndex(index));
EXPECT_EQ(tree.index(), TreeIndex(index));
EXPECT_EQ(tree.height(), height);
EXPECT_EQ(tree.base_mobod(), MobodIndex(base_mobod));
EXPECT_EQ(tree.last_mobod(), MobodIndex(last_mobod));
EXPECT_EQ(tree.num_mobods(), num_mobods);
EXPECT_EQ(tree.q_start(), q_start);
EXPECT_EQ(tree.nq(), nq);
EXPECT_EQ(tree.v_start(), v_start);
EXPECT_EQ(tree.nv(), nv);
EXPECT_EQ(&tree.front(), &forest.mobods(MobodIndex(base_mobod)));
EXPECT_EQ(&tree.back(), &forest.mobods(MobodIndex(last_mobod)));
EXPECT_EQ(tree.begin(), &tree.front());
EXPECT_EQ(tree.end(), &tree.back() + 1);
};
// clang-format off
// index height base_ last_ num_mobods qstart nq vstart nv
tree_check(0, 4, 1, 6, 6, 0, 12, 0, 11);
tree_check(1, 6, 7, 14, 8, 12, 14, 11, 13);
tree_check(2, 1, 15, 15, 1, 26, 7, 24, 6);
// clang-format on
// Sample some q's and v's to see if they can find their tree and mobod.
EXPECT_EQ(forest.q_to_tree(9), TreeIndex(0));
EXPECT_EQ(forest.q_to_tree(19), TreeIndex(1));
EXPECT_EQ(forest.q_to_tree(30), TreeIndex(2));
EXPECT_EQ(forest.v_to_tree(9), TreeIndex(0));
EXPECT_EQ(forest.v_to_tree(19), TreeIndex(1));
EXPECT_EQ(forest.v_to_tree(29), TreeIndex(2));
EXPECT_EQ(forest.q_to_mobod(9), MobodIndex(4));
EXPECT_EQ(forest.q_to_mobod(20), MobodIndex(9));
EXPECT_EQ(forest.q_to_mobod(30), MobodIndex(15));
EXPECT_EQ(forest.v_to_mobod(9), MobodIndex(5));
EXPECT_EQ(forest.v_to_mobod(20), MobodIndex(11));
EXPECT_EQ(forest.v_to_mobod(29), MobodIndex(15));
// mobod.subtree_velocities() reports which dofs are in the subtree
// rooted at a given Mobod as (start, ndofs). Check some of them.
auto find_subv = [&forest](int mobod_index) -> pair<int, int> {
return forest.mobods(MobodIndex(mobod_index)).subtree_velocities();
};
EXPECT_EQ(find_subv(0), pair(0, 30)); // World
EXPECT_EQ(find_subv(1), pair(0, 11)); // base tree0
EXPECT_EQ(find_subv(7), pair(11, 13)); // base tree1
EXPECT_EQ(find_subv(15), pair(24, 6)); // base tree2
EXPECT_EQ(find_subv(3), pair(7, 1)); // terminal
EXPECT_EQ(find_subv(4), pair(8, 3)); // nonterminal
EXPECT_EQ(find_subv(8), pair(17, 7)); // tree1 nonterminal
EXPECT_EQ(find_subv(10), pair(19, 4));
EXPECT_EQ(find_subv(14), pair(23, 1)); // tree1 terminal
// mobod.outboard_velocities() is the same but excludes inboard dofs of
// the selected Mobod.
auto find_outv = [&forest](int mobod_index) -> pair<int, int> {
return forest.mobods(MobodIndex(mobod_index)).outboard_velocities();
};
EXPECT_EQ(find_outv(0), pair(0, 30)); // Same Mobods as above
EXPECT_EQ(find_outv(1), pair(6, 5)); // base tree0
EXPECT_EQ(find_outv(7), pair(17, 7)); // base tree1
EXPECT_EQ(find_outv(15), pair(30, 0)); // base tree2
EXPECT_EQ(find_outv(3), pair(8, 0)); // terminal
EXPECT_EQ(find_outv(4), pair(9, 2)); // nonterminal
EXPECT_EQ(find_outv(8), pair(18, 6)); // tree1 nonterminal
EXPECT_EQ(find_outv(10), pair(20, 3));
EXPECT_EQ(find_outv(14), pair(24, 0)); // tree1 terminal
}
/* Starting with the same graph as the previous test, change the tree1
options to use an RpyFloating base and tree2 to use a fixed (Weld) base. */
GTEST_TEST(SpanningForest, MultipleBranchesBaseJointOptions) {
const ModelInstanceIndex left_instance(5), right_instance(6),
free_link_instance(7); // arbitrary
LinkJointGraph graph =
MakeMultiBranchGraph(left_instance, right_instance, free_link_instance);
const SpanningForest& forest = graph.forest();
graph.SetForestBuildingOptions(left_instance,
ForestBuildingOptions::kUseRpyFloatingJoints);
graph.SetForestBuildingOptions(right_instance,
ForestBuildingOptions::kUseFixedBase);
EXPECT_TRUE(graph.BuildForest());
EXPECT_EQ(forest.options(), ForestBuildingOptions::kDefault);
EXPECT_EQ(forest.options(left_instance),
ForestBuildingOptions::kUseRpyFloatingJoints);
EXPECT_EQ(forest.options(right_instance),
ForestBuildingOptions::kUseFixedBase);
EXPECT_EQ(forest.options(free_link_instance),
ForestBuildingOptions::kDefault);
// Check graph augmentation.
EXPECT_EQ(graph.num_user_links(), 16);
EXPECT_EQ(ssize(graph.links()), 16); // no links added
EXPECT_EQ(graph.num_user_joints(), 12);
EXPECT_EQ(ssize(graph.joints()), 15); // modeling adds 3 joints to World
// We should have 12 user-added revolute joints, plus one RpyFloating, one
// Weld, and one QuaternionFloating joint added.
EXPECT_EQ(ssize(forest.trees()), 3);
EXPECT_EQ(ssize(forest.mobods()), 16); // includes World
EXPECT_EQ(ssize(forest.welded_mobods()), 1); // just World
EXPECT_EQ(forest.num_positions(), 25); // 12 + 6 + 0 + 7
EXPECT_EQ(forest.num_velocities(), 24); // 12 + 6 + 0 + 6
// Reminder: left->tree0, right->tree1, free link->tree2.
const SpanningForest::Tree& tree0 = forest.trees(TreeIndex(0));
const SpanningForest::Tree& tree1 = forest.trees(TreeIndex(1));
const SpanningForest::Tree& tree2 = forest.trees(TreeIndex(2));
// The base Mobod of tree2 is now welded to World so is anchored. (A tree's
// "front" is the base Mobod for that tree.) The corresponding Links should
// also know their anchored status.
EXPECT_FALSE(tree0.front().is_anchored());
EXPECT_TRUE(tree1.front().is_anchored());
EXPECT_FALSE(tree2.front().is_anchored());
EXPECT_FALSE(graph.links(tree0.front().link_ordinal()).is_anchored());
EXPECT_TRUE(graph.links(tree1.front().link_ordinal()).is_anchored());
EXPECT_FALSE(graph.links(tree2.front().link_ordinal()).is_anchored());
// There is only the World composite, but now tree1's base link is included.
EXPECT_EQ(ssize(graph.link_composites()), 1); // just World
EXPECT_EQ(ssize(graph.link_composites(LinkCompositeIndex(0)).links), 2);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links[0],
graph.world_link().index());
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links[1],
graph.links(tree1.front().link_ordinal()).index());
// Similarly, there is only one WeldedMobods group, containing just World
// and tree1's base
EXPECT_EQ(ssize(forest.welded_mobods()), 1);
EXPECT_EQ(ssize(forest.welded_mobods(WeldedMobodsIndex(0))), 2);
EXPECT_EQ(forest.welded_mobods(WeldedMobodsIndex(0))[0],
forest.world_mobod().index());
EXPECT_EQ(forest.welded_mobods(WeldedMobodsIndex(0))[1], tree1.base_mobod());
}
/* Verify that our base body choice policy works as intended. The policy
applies to any disconnected subgraph with at least one joint:
1 pick the link that appears as a child least often
2 to break a tie, pick the one that appears as a parent _most_ often
3 if there is still a tie, pick the lowest-numbered link.
We'll also verify that parent->child direction is preserved as inboard->outboard
when possible, but reversed otherwise.
To test we use these subgraphs, with no connections to World. The link that
should be chosen for the base body is marked with an asterisk:
-> gives joint's parent->child direction
{Links}
{1} <- {2*} -> {3} rule 1
{4} -> {5} <- {6*} -> {7} rule 2 ({4}, {6} tied by rule 1)
{8*} -> {9} <- {10} rule 3 ({8}, {10} tied by rules 1 & 2)
After depth-first numbering, the corresponding trees in the forest should look
like this. Mobod numbers are shown, with the link in {}.
6{4} 10{10}
2{1} 3{3} 5{5} 7{7} 9{9}
1{2} 4{6} 8{8}
..............0{0}...............
Joints {4,5} and {10,9} have to be reversed to make the trees.
*/
GTEST_TEST(SpanningForest, BaseBodyChoicePolicy) {
LinkJointGraph graph;
graph.RegisterJointType("revolute", 1, 1);
for (int i = 1; i <= 10; ++i)
graph.AddLink("link" + std::to_string(i), default_model_instance());
const std::vector<std::pair<int, int>> joints{{2, 1}, {2, 3}, {4, 5}, {6, 5},
{6, 7}, {8, 9}, {10, 9}};
for (int i = 0; i < ssize(joints); ++i) {
const auto joint = joints[i];
graph.AddJoint("joint" + std::to_string(i), default_model_instance(),
"revolute", BodyIndex(joint.first), BodyIndex(joint.second));
}
EXPECT_TRUE(graph.BuildForest());
const SpanningForest& forest = graph.forest();
EXPECT_EQ(graph.num_user_joints(), 7);
EXPECT_EQ(ssize(graph.joints()), 10); // 3 ephemeral base joints
EXPECT_EQ(ssize(forest.trees()), 3);
EXPECT_EQ(forest.trees(TreeIndex(0)).base_mobod(), MobodIndex(1));
EXPECT_EQ(forest.trees(TreeIndex(1)).base_mobod(), MobodIndex(4));
EXPECT_EQ(forest.trees(TreeIndex(2)).base_mobod(), MobodIndex(8));
// Check that only joints {4,5} and {10,9} were reversed. (The last three
// entries are the added base joints.)
const std::vector<bool> expect_reversed{false, false, true, false, false,
false, true, false, false, false};
for (auto joint : graph.joints()) {
const auto& mobod = forest.mobods(joint.mobod_index());
EXPECT_EQ(mobod.is_reversed(), expect_reversed[joint.index()]);
}
}
/* Verify that we can build a good forest for a serial chain, some static and
floating links, and some simple composites, obeying forest building options.
Links can become static either by being members of a static model instance,
or by having been specified with the kStatic link flag; we test both of those
here. Forest building should add a weld joint to World for every static link
unless there is already an explicit weld; we'll check that.
LinkComposites are always computed and consist of subgraphs of links that are
mutually welded together (directly or indirectly). Depending on forest building
options, we may use a single Mobod for a LinkComposite, or we may use a Mobod
for each of those welded-together links. In the latter case we also compute
"welded Mobod" groups consisting of Mobods that are mutually interconnected by
weld mobilizers (directly or indirectly). When we're modeling each
LinkComposite with just one Mobod, there won't be any welded-together Mobods.
By convention, there will still be one welded Mobod group, consisting just
of the World Mobod.
We'll also check that coordinates are assigned properly and that pre-calculated
forest counts are correct.
The LinkJointGraph
------------------
-> user supplied rotational joint
=> user supplied weld joint
(arrow indicates given parent->child ordering)
world->link1->link2->link3->link4->link5
static6 (no joint, static model instance)
=>static7 (weld provided, static model instance)
static8 (no joint, static link)
free9 (no joint)
link10=>base11* (free floating but welded together)
* link10 would be the preferred base link but link 11 "base11" is marked
"must be base link" so we have to use a reversed mobilizer there
SerialChain 1 (don't merge LinkComposites)
------------------------------------------
≡> added weld joint [mobods]
6> added floating joint {links}
When building the forest in the mode where every Link gets its own Mobod
(even if Links are welded together) the SpanningForest should have 6 trees of
Mobods (World is not in a tree):
tree world [0]
0 [1-5] ->link1->link2->link3->link4->link5
1 [6] =>static7
2 [7] ≡>static6 (added weld)
3 [8] ≡>static8 (added weld)
4 [9-10] 6>base11=>link10 (added 6dof, reversed the user's weld)
5 [11] 6>free9 (added 6dof, free bodies are always last)
LinkComposites: {0 7 6 8} {11 10}
Welded Mobods groups: [0 6 7 8] [9 10]
The particular ordering results from (a) user-supplied Joints get processed
before added ones, and (b) static model instance Links get welded prior
to individually-specified static Links in non-static model instances.
However, note that we do not promise any particular ordering other than
(1) World is always present and is first, and (2) the active link comes first
in any LinkComposite.
We will also vary this graph in several ways and retest. The details are
described in the code below.
*/
GTEST_TEST(SpanningForest, SerialChainAndMore) {
LinkJointGraph graph;
graph.RegisterJointType("revolute", 1, 1);
EXPECT_EQ(ssize(graph.joint_traits()), 4); // Built-ins plus "revolute".
EXPECT_TRUE(graph.IsJointTypeRegistered("revolute"));
EXPECT_FALSE(graph.IsJointTypeRegistered("prismatic"));
// We'll add the chain and other moving elements to this model instance.
const ModelInstanceIndex model_instance(5);
// Put static bodies in this model instance.
const ModelInstanceIndex static_model_instance(100);
BodyIndex parent = graph.AddLink("link1", model_instance);
graph.AddJoint("pin1", model_instance, "revolute", world_index(), parent);
for (int i = 2; i <= 5; ++i) {
BodyIndex child = graph.AddLink("link" + std::to_string(i), model_instance);
graph.AddJoint("pin" + std::to_string(i), model_instance, "revolute",
parent, child);
parent = child;
}
graph.AddLink("static6", static_model_instance);
const BodyIndex static7_index =
graph.AddLink("static7", static_model_instance);
const BodyIndex static8_index =
graph.AddLink("static8", model_instance, LinkFlags::kStatic);
// Manually adding a weld to World is allowable for a static Link.
const JointIndex static7_joint_index =
graph.AddJoint("static7_weld", model_instance, "weld",
graph.world_link().index(), static7_index);
// Now add a free link and a free-floating pair.
graph.AddLink("free9", model_instance);
const BodyIndex link10_index = graph.AddLink("link10", model_instance);
const BodyIndex base11_index =
graph.AddLink("base11", model_instance, LinkFlags::kMustBeBaseBody);
const JointIndex joint_10_11_index = graph.AddJoint(
"weld", model_instance, "weld", link10_index, base11_index);
// SerialChain 1 (not merging welded Links onto one Mobod)
// -------------------------------------------------------
graph.ResetForestBuildingOptions(); // Unnecessary; just being tidy.
graph.SetForestBuildingOptions(static_model_instance,
ForestBuildingOptions::kStatic);
EXPECT_TRUE(graph.BuildForest());
const SpanningForest& forest = graph.forest();
EXPECT_TRUE(graph.forest_is_valid());
// Verify that ChangeJointType() rejects an attempt to change a static link's
// weld to something articulated. Also check that when it fails, it doesn't
// invalidate the currently-valid forest.
// static7 is in static_model_instance.
DRAKE_EXPECT_THROWS_MESSAGE(
graph.ChangeJointType(static7_joint_index, "revolute"),
"ChangeJointType.*can't change type.*static7_weld.*instance 5.*"
"weld to revolute.*because.*connects static .*static7.*World.*");
EXPECT_TRUE(graph.forest_is_valid());
// static8 is explicitly flagged static but doesn't have a user-defined
// joint. Verify that ChangeJointType() refuses to operate on an ephemeral
// (added) joint.
const JointIndex static8_joint_index =
graph.link_by_index(static8_index).inboard_joint_index();
DRAKE_EXPECT_THROWS_MESSAGE(
graph.ChangeJointType(static8_joint_index, "revolute"),
"ChangeJointType.*can't change the type.*ephemeral.*static8.* only "
"user-defined.*");
EXPECT_TRUE(graph.forest_is_valid());
// Should have added four ephemeral joints to the graph.
EXPECT_EQ(graph.num_user_joints(), 7);
EXPECT_EQ(ssize(graph.joints()), 11);
const JointIndex base11_joint_index(9); // See above picture.
const JointIndex free9_joint_index(10);
EXPECT_EQ(graph.joint_by_index(base11_joint_index).traits_index(),
LinkJointGraph::quaternion_floating_joint_traits_index());
EXPECT_EQ(graph.joint_by_index(free9_joint_index).traits_index(),
LinkJointGraph::quaternion_floating_joint_traits_index());
const std::vector<BodyIndex> link_composites0{BodyIndex(0), BodyIndex(7),
BodyIndex(6), BodyIndex(8)};
const std::vector<BodyIndex> link_composites1{BodyIndex(11), BodyIndex(10)};
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links,
link_composites0);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(1)).links,
link_composites1);
EXPECT_FALSE(graph.link_composites(LinkCompositeIndex(0)).is_massless);
EXPECT_FALSE(graph.link_composites(LinkCompositeIndex(1)).is_massless);
EXPECT_EQ(ssize(forest.mobods()), 12);
EXPECT_EQ(ssize(forest.trees()), 6);
EXPECT_EQ(forest.num_positions(), 19);
EXPECT_EQ(forest.num_velocities(), 17);
// Check inboard & outboard coordinate counts.
// Counts for World.
EXPECT_EQ(forest.world_mobod().nq(), 0);
EXPECT_EQ(forest.world_mobod().nv(), 0);
EXPECT_EQ(forest.world_mobod().nq_inboard(), 0);
EXPECT_EQ(forest.world_mobod().nv_inboard(), 0);
EXPECT_EQ(forest.world_mobod().nq_outboard(), forest.num_positions());
EXPECT_EQ(forest.world_mobod().nv_outboard(), forest.num_velocities());
EXPECT_EQ(forest.world_mobod().num_subtree_mobods(), ssize(forest.mobods()));
// Counts for generic middle Mobod.
const SpanningForest::Mobod& mobod_for_link3 =
forest.mobods(graph.link_by_index(BodyIndex(3)).mobod_index());
EXPECT_EQ(graph.links(mobod_for_link3.link_ordinal()).index(), BodyIndex(3));
EXPECT_EQ(mobod_for_link3.q_start(), 2);
EXPECT_EQ(mobod_for_link3.v_start(), 2);
EXPECT_EQ(mobod_for_link3.nq(), 1);
EXPECT_EQ(mobod_for_link3.nv(), 1);
EXPECT_EQ(mobod_for_link3.nq_inboard(), 3);
EXPECT_EQ(mobod_for_link3.nv_inboard(), 3);
EXPECT_EQ(mobod_for_link3.nq_outboard(), 2);
EXPECT_EQ(mobod_for_link3.nv_outboard(), 2);
EXPECT_EQ(mobod_for_link3.num_subtree_mobods(), 3);
// Counts for a Mobod with nq != nv.
const SpanningForest::Mobod& mobod_for_base11 =
forest.mobods(graph.link_by_index(BodyIndex(11)).mobod_index());
EXPECT_EQ(mobod_for_base11.q_start(), 5);
EXPECT_EQ(mobod_for_base11.v_start(), 5);
EXPECT_EQ(mobod_for_base11.nq(), 7);
EXPECT_EQ(mobod_for_base11.nv(), 6);
EXPECT_EQ(mobod_for_base11.nq_inboard(), 7);
EXPECT_EQ(mobod_for_base11.nv_inboard(), 6);
EXPECT_EQ(mobod_for_base11.nq_outboard(), 0);
EXPECT_EQ(mobod_for_base11.nv_outboard(), 0);
EXPECT_EQ(mobod_for_base11.num_subtree_mobods(), 2);
const std::vector<MobodIndex> welded_mobods0{MobodIndex(0), MobodIndex(6),
MobodIndex(7), MobodIndex(8)};
const std::vector<MobodIndex> welded_mobods1{MobodIndex(9), MobodIndex(10)};
const std::vector expected_welded_mobods{welded_mobods0, welded_mobods1};
EXPECT_EQ(forest.welded_mobods(), expected_welded_mobods);
auto find_outv = [&forest](int mobod_index) -> pair<int, int> {
return forest.mobods(MobodIndex(mobod_index)).outboard_velocities();
};
EXPECT_EQ(find_outv(0), pair(0, 17)); // World
EXPECT_TRUE(forest.mobods(MobodIndex(1)).is_base_body()); // Base bodies
EXPECT_TRUE(forest.mobods(MobodIndex(7)).is_base_body());
EXPECT_TRUE(forest.mobods(MobodIndex(9)).is_base_body());
EXPECT_TRUE(forest.mobods(MobodIndex(11)).is_base_body());
EXPECT_EQ(find_outv(1), pair(1, 4));
EXPECT_EQ(find_outv(6), pair(5, 0));
EXPECT_EQ(find_outv(9), pair(11, 0));
EXPECT_EQ(find_outv(11), pair(17, 0));
EXPECT_FALSE(forest.mobods(MobodIndex(3)).is_base_body()); // Generic case
EXPECT_EQ(find_outv(3), pair(3, 2));
/* SerialChain 2 (merge link composites)
----------------------------------------
If instead we ask to merge welded Links we should get a much smaller
forest:
tree {world static7 static6 static8} [0]
0 [1-5] ->link1->link2->link3->link4->link5
1 [6] 6>{base11<=link10} (added 6dof, unmodeled weld)
2 [7] 6>free9 (added 6dof, free bodies are always last)
Link Composites: {0 7 6 8} {11 10} (no change)
Welded Mobods groups: [0] (just the World group) */
graph.ResetForestBuildingOptions(); // Restore default options.
graph.SetGlobalForestBuildingOptions(
ForestBuildingOptions::kMergeLinkComposites);
graph.SetForestBuildingOptions(static_model_instance,
ForestBuildingOptions::kMergeLinkComposites |
ForestBuildingOptions::kStatic);
EXPECT_TRUE(graph.BuildForest());
// The graph shouldn't change from SpanningForest 1, but the forest will.
EXPECT_EQ(ssize(graph.joints()) - graph.num_user_joints(), 4);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links,
link_composites0);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(1)).links,
link_composites1);
EXPECT_EQ(ssize(forest.mobods()), 8);
EXPECT_EQ(ssize(forest.trees()), 3);
EXPECT_EQ(ssize(forest.welded_mobods()), 1); // Just World.
/* SerialChain 3 (merge composites except for 10 & 11)
------------------------------------------------------
We can optionally insist that a weld joint within a composite that would
otherwise be ignored is actually modeled with a weld mobilizer (useful if
you need to know reaction forces within that weld). We'll rebuild but
specifying that the joint between link10 and link11 must be modeled. That
should produce this forest:
tree {world static7 static6 static8} [0]
0 [1-5] ->link1->link2->link3->link4->link5
1 [6-7] 6>{base11<=link10} (added 6dof, weld is now modeled)
2 [8] 6>free9 (added 6dof, free bodies are always last)
Link Composites: {0 7 6 8} {11 10} (no change)
Welded Mobods groups: [0] [6 7] */
// Now force one of the joints in a composite to be modeled (meaning it
// should get its own Mobod). This should split that composite into
// two Mobods, which should be noted as a Welded Mobods group.
graph.ChangeJointFlags(joint_10_11_index, JointFlags::kMustBeModeled);
// Built the forest with same options as used for 2a.
EXPECT_TRUE(graph.BuildForest());
EXPECT_EQ(ssize(forest.mobods()), 9);
EXPECT_EQ(ssize(forest.trees()), 3);
EXPECT_EQ(ssize(forest.welded_mobods()), 2);
const std::vector<MobodIndex> now_expected{MobodIndex(6), MobodIndex(7)};
EXPECT_EQ(forest.welded_mobods(WeldedMobodsIndex(1)), now_expected);
/* SerialChain 4 (merge composites and use a fixed base)
--------------------------------------------------------
Finally, we'll restore joint 10-11 to its default setting and build again but
this time with the kUseFixedBase option for model_instance.
That means we'll use weld joints rather than floating joints for links that
have no path to World in the input graph. Now we expect this forest:
tree {world static7 static6 static8 base11 link10 free9} [0]
0 [1-5] ->link1->link2->link3->link4->link5
Link Composites: {0 7 6 8 11 10 9}
Welded Mobods groups: [0] (just World) */
// Put the joint back the way we found it.
graph.ChangeJointFlags(joint_10_11_index, JointFlags::kDefault);
graph.ResetForestBuildingOptions(); // Back to defaults.
graph.SetGlobalForestBuildingOptions(
ForestBuildingOptions::kMergeLinkComposites);
// Caution: we must specify all the forest building options we want for
// a model instance; it won't inherit any of the global ones if set.
graph.SetForestBuildingOptions(model_instance,
ForestBuildingOptions::kMergeLinkComposites |
ForestBuildingOptions::kUseFixedBase);
graph.SetForestBuildingOptions(static_model_instance,
ForestBuildingOptions::kMergeLinkComposites |
ForestBuildingOptions::kStatic);
EXPECT_TRUE(graph.BuildForest());
EXPECT_EQ(ssize(forest.mobods()), 6);
EXPECT_EQ(ssize(forest.trees()), 1);
EXPECT_EQ(ssize(forest.welded_mobods()), 1); // Just World.
const std::vector<BodyIndex> expected_link_composite{
BodyIndex(0), BodyIndex(7), BodyIndex(6), BodyIndex(8),
BodyIndex(11), BodyIndex(10), BodyIndex(9)};
EXPECT_EQ(ssize(graph.link_composites()), 1);
EXPECT_EQ(graph.link_composites(LinkCompositeIndex(0)).links,
expected_link_composite);
}
/* Topological loops formed entirely by welds can be handled specially when
we're merging LinkComposites onto single Mobods. We build a Forest containing
a number of kinematic loops and subgraphs of welded bodies.
The input is given as three unconnected subgraphs. Joints are shown with
parent->child direction. Double bars are welds, single bars are moving joints.
Links {0-13} are shown in braces, joint numbers 0-13 are plain.
Link/Joint graph as input
===> weld
12 11 9 ---> revolute or prismatic
{0}<==={5}===>{7}--->{2} {1} link # in braces
World ^ |10 | 10 joint # plain
13‖ v |8
{12} {11}<---+
3 0 7 4
{3}--->{13}<==={1}--->{10}===>{6}
2‖ ^ 5‖ ‖
v ‖1 v ‖6
{4}=====+ {8}<====+
{9}
When we build the forest, we have to provide every link with a path to World.
We'll first process the upper graph which already starts at World. Then we
have to pick a base body for the next graph. Link {3} should be chosen since
it appears only as a parent; it gets floating joint 14. Link {9} will also be
a base body; it gets floating joint 15.
There are three loops in this graph: {7-2-11}, {13-1-4}, and {10-6-8}. The
forest-building algorithm will encounter them in that order. The last two loops
are formed entirely of welds. When modeling in the mode where every Joint gets a
Mobod all of these must be broken by adding shadow links. In each case the loop
joint will be between two bodies at the same level in their tree, so the choice
of which one to split should be made so that the parent->child orientation in
the graph is preserved in the inboard->outboard order of the tree, requiring
that the child Link is the one split. (It is easier to see the levels in the
forest diagram below.) As a result, Link {11} will be split with shadow link
{14*} on Joint 8, Link {1} gets shadow {15*} on weld Joint 1, and Link {8} gets
shadow {16*} on weld Joint 6.
Therefore we expect the following Composites, with the "World" Composite first:
{0, 5, 7, 12}, {13, 1, 4, 15*}, {10, 6, 8, 16*}
Note that the _active_ Link (the one on a moving joint) is always listed first
in a LinkComposite (World comes first in the World composite). The remaining
non-composite links are {3}, {9}, {2}, {11}, and {14*}.
Forest building should start with Link {5} since that is the only direct
connection to World in the input ({3} and {9} get connected later). If we're
giving every Link its own mobilizer (rather than making composites from
welded-together ones) we expect this forest of 3 trees and 17 Mobods:
level 6 12{16*} .... ... loop constraint
. {1} link # in braces
level 5 11{6} 13{8} 10 mobod # plain
level 4 4{14*} ... 10{10} . 15{15*}
. ..
level 3 3{2} 5{11} 9{1}.. 14{4}
level 2 2{7} 6{12} 8{13}
base mobods 1{5} 7{3} 16{9}
\ | /
World ............0{0}.............
Note that the Mobod numbers shown here (and in all the tests) are _after_
renumbering into depth first order, not the order in which the Mobods were
assigned.
Some of the Links are welded together. We call those LinkComposites even
though each Link has its own Mobod. Those are:
{0 5 7 12} {13 1 4 15} {10 6 8 16}
The corresponding Mobods are in WeldedMobod groups:
[0 1 2 6] [8 9 14 15] [10 11 13 12]
Remodeling with composite link merging turned on should immediately create
composite {0 5 7 12} on mobod 0, then see outboard links {2} and {11} as new
base bodies and grow those two trees, discovering a loop at joint 8. As before,
Link {11} gets split with a shadow link {14} for joint 8. Then it
should choose link {3} as a base link and add floating joint 14, and grow that
tree. Finally it makes free link {9} a base body. The forest should then look
like this:
level 3 6{10 6 8}
level 2 2{14} 5{13 1 4}
base mobods 1{2} 3{11} 4{3} 7{9} (four trees)
\ \ | /
World ...........0{0 5 7 12}......
In this case we don't need to split the all-Weld loops since they are now
just composite links {0 5 7 12} {13 1 4} {10 6 8}. There are no Welded
Mobods (except World alone). */
GTEST_TEST(SpanningForest, WeldedSubgraphs) {
LinkJointGraph graph;
graph.RegisterJointType("revolute", 1, 1);
graph.RegisterJointType("prismatic", 1, 1);
EXPECT_EQ(ssize(graph.joint_traits()), 5); // Predefined+revolute+prismatic.
const ModelInstanceIndex model_instance(5); // Arbitrary.
// Define the forest.
for (int i = 1; i <= 13; ++i)
graph.AddLink("link" + std::to_string(i), model_instance);
// clang-format off
// Add joints: type parent child
std::vector<std::tuple<std::string, int, int>> joints{
{"weld", 1, 13}, {"weld", 4, 1}, {"weld", 13, 4}, // loop 1 4 13
{"revolute", 3, 13},
{"weld", 10, 6}, {"weld", 10, 8}, {"weld", 6, 8}, // loop 6 8 10
{"prismatic", 1, 10},
{"prismatic", 2, 11}, {"prismatic", 7, 2}, {"prismatic", 7, 11}, // loop
// 2 7 11
{"weld", 5, 7}, {"weld", 5, 0}, {"weld", 12, 5}
};
// clang-format on
for (int i = 0; i < ssize(joints); ++i) {
const auto& joint = joints[i];
graph.AddJoint("joint" + std::to_string(i), model_instance,
std::get<0>(joint), BodyIndex(std::get<1>(joint)),
BodyIndex(std::get<2>(joint)));
}
EXPECT_EQ(ssize(graph.links()), 14); // Includes World.
EXPECT_EQ(ssize(graph.joints()), 14);
EXPECT_TRUE(graph.BuildForest());
const SpanningForest& forest = graph.forest();
EXPECT_EQ(graph.num_user_links(), 14); // Same as before building.
EXPECT_EQ(graph.num_user_joints(), 14);
EXPECT_EQ(ssize(graph.links()), 17); // +3 shadows.
EXPECT_EQ(ssize(graph.joints()), 16); // +2 floating joints to world.
EXPECT_EQ(ssize(graph.loop_constraints()), 3);
// Check that the shadows are connected up properly. See the test comment
// above for why we expect these particular links to get split.
for (BodyIndex link(14); link <= 16; ++link)
EXPECT_TRUE(graph.link_by_index(link).is_shadow());
EXPECT_EQ(graph.link_by_index(BodyIndex(14)).primary_link(), 11);
EXPECT_EQ(graph.link_by_index(BodyIndex(11)).num_shadows(), 1);
EXPECT_EQ(graph.link_by_index(BodyIndex(15)).primary_link(), 1);
EXPECT_EQ(graph.link_by_index(BodyIndex(1)).num_shadows(), 1);
EXPECT_EQ(graph.link_by_index(BodyIndex(16)).primary_link(), 8);
EXPECT_EQ(graph.link_by_index(BodyIndex(8)).num_shadows(), 1);
// Check that we built the LinkComposites properly (see above).