Skip to content

Commit 52d1ba1

Browse files
committed
Adds misc algorithms over graph and forest
1 parent 1464637 commit 52d1ba1

6 files changed

+693
-27
lines changed

multibody/topology/link_joint_graph.cc

+163
Original file line numberDiff line numberDiff line change
@@ -704,6 +704,169 @@ bool LinkJointGraph::link_is_static(const Link& link) const {
704704
ForestBuildingOptions::kStatic);
705705
}
706706

707+
/* Runs through the Mobods in the model but records the (active) Link
708+
indexes rather than the Mobod indexes. */
709+
std::vector<LinkIndex> LinkJointGraph::FindPathFromWorld(
710+
LinkIndex link_index) const {
711+
ThrowIfForestNotBuiltYet(__func__);
712+
const SpanningForest::Mobod* mobod =
713+
&forest().mobods()[link_to_mobod(link_index)];
714+
std::vector<LinkIndex> path(mobod->level() + 1);
715+
while (mobod->inboard().is_valid()) {
716+
const Link& link = links(mobod->link_ordinal());
717+
path[mobod->level()] = link.index(); // Active Link if composite.
718+
mobod = &forest().mobods(mobod->inboard());
719+
}
720+
DRAKE_DEMAND(mobod->is_world());
721+
path[0] = LinkIndex(0);
722+
return path;
723+
}
724+
725+
LinkIndex LinkJointGraph::FindFirstCommonAncestor(LinkIndex link1_index,
726+
LinkIndex link2_index) const {
727+
ThrowIfForestNotBuiltYet(__func__);
728+
const MobodIndex mobod_ancestor = forest().FindFirstCommonAncestor(
729+
link_to_mobod(link1_index), link_to_mobod(link2_index));
730+
const Link& ancestor_link =
731+
links(forest().mobod_to_link_ordinal(mobod_ancestor));
732+
return ancestor_link.index();
733+
}
734+
735+
std::vector<LinkIndex> LinkJointGraph::FindSubtreeLinks(
736+
LinkIndex link_index) const {
737+
ThrowIfForestNotBuiltYet(__func__);
738+
const MobodIndex root_mobod_index = link_to_mobod(link_index);
739+
return forest().FindSubtreeLinks(root_mobod_index);
740+
}
741+
742+
// Our link_composites collection doesn't include lone Links that aren't welded
743+
// to anything. The return from this function must include every Link, with
744+
// the World link in the first set (even if nothing is welded to it).
745+
std::vector<std::set<LinkIndex>> LinkJointGraph::GetSubgraphsOfWeldedLinks()
746+
const {
747+
ThrowIfForestNotBuiltYet(__func__);
748+
749+
std::vector<std::set<LinkIndex>> subgraphs;
750+
751+
// First, collect all the precomputed Link Composites. World is always
752+
// the first one, even if nothing is welded to it.
753+
for (const LinkComposite& composite : link_composites()) {
754+
subgraphs.emplace_back(
755+
std::set<LinkIndex>(composite.links.cbegin(), composite.links.cend()));
756+
}
757+
758+
// Finally, make one-Link subgraphs for Links that aren't in any composite.
759+
for (const Link& link : links()) {
760+
if (link.composite().has_value()) continue;
761+
subgraphs.emplace_back(std::set<LinkIndex>{link.index()});
762+
}
763+
764+
return subgraphs;
765+
}
766+
767+
// Strategy here is to make repeated use of CalcLinksWeldedTo(), separating
768+
// the singleton sets from the actually-welded sets, and then move the
769+
// singletons to the end to match what GetSubgraphsOfWeldedLinks() does.
770+
std::vector<std::set<LinkIndex>> LinkJointGraph::CalcSubgraphsOfWeldedLinks()
771+
const {
772+
// Work with ordinals rather than indexes.
773+
std::vector<bool> visited(num_user_links(), false);
774+
775+
// World always comes first, even if it is alone.
776+
std::vector<std::set<LinkIndex>> subgraphs{CalcLinksWeldedTo(LinkIndex(0))};
777+
for (LinkIndex index : subgraphs[0]) visited[index_to_ordinal(index)] = true;
778+
779+
std::vector<std::set<LinkIndex>> singletons;
780+
// If a Forest was already built, there may be shadow links added to
781+
// the graph -- don't process those here.
782+
for (LinkOrdinal link_ordinal(1); link_ordinal < num_user_links();
783+
++link_ordinal) {
784+
const Link& link = links(link_ordinal);
785+
if (link.is_shadow() || visited[link_ordinal]) continue;
786+
std::set<LinkIndex> welded_links = CalcLinksWeldedTo(link.index());
787+
for (LinkIndex index : welded_links)
788+
visited[index_to_ordinal(index)] = true;
789+
if (ssize(welded_links) == 1) {
790+
singletons.emplace_back(std::move(welded_links));
791+
} else {
792+
subgraphs.emplace_back(std::move(welded_links));
793+
}
794+
}
795+
796+
// Now move all the singletons onto the end of the subgraphs list.
797+
for (auto& singleton : singletons)
798+
subgraphs.emplace_back(std::move(singleton));
799+
800+
return subgraphs;
801+
}
802+
803+
// If the Link isn't part of a LinkComposite just return the Link. Otherwise,
804+
// return all the Links in its LinkComposite.
805+
std::set<LinkIndex> LinkJointGraph::GetLinksWeldedTo(
806+
LinkIndex link_index) const {
807+
ThrowIfForestNotBuiltYet(__func__);
808+
DRAKE_DEMAND(link_index.is_valid());
809+
DRAKE_THROW_UNLESS(has_link(link_index));
810+
const Link& link = link_by_index(link_index);
811+
const std::optional<LinkCompositeIndex> composite_index = link.composite();
812+
if (!composite_index.has_value()) return std::set<LinkIndex>{link_index};
813+
const std::vector<LinkIndex>& welded_links =
814+
link_composites(*composite_index).links;
815+
return std::set<LinkIndex>(welded_links.cbegin(), welded_links.cend());
816+
}
817+
818+
// Without a Forest we don't have LinkComposites available so recursively
819+
// chase Weld joints instead.
820+
std::set<LinkIndex> LinkJointGraph::CalcLinksWeldedTo(
821+
LinkIndex link_index) const {
822+
std::set<LinkIndex> result;
823+
AppendLinksWeldedTo(link_index, &result);
824+
return result;
825+
}
826+
827+
void LinkJointGraph::AppendLinksWeldedTo(LinkIndex link_index,
828+
std::set<LinkIndex>* result) const {
829+
DRAKE_DEMAND(result != nullptr);
830+
DRAKE_DEMAND(link_index.is_valid());
831+
DRAKE_THROW_UNLESS(has_link(link_index));
832+
DRAKE_DEMAND(!result->contains(link_index));
833+
834+
const Link& link = link_by_index(link_index);
835+
836+
// A Link is always considered welded to itself.
837+
result->insert(link_index);
838+
839+
// For World we have to look for static links and pretend they are welded to
840+
// World. (Links might have been explicitly flagged as static or part of a
841+
// static model instance.)
842+
if (link.is_world()) {
843+
for (const Link& maybe_static : links()) {
844+
if (result->contains(maybe_static.index())) continue;
845+
if (link_is_static(maybe_static))
846+
AppendLinksWeldedTo(maybe_static.index(), &*result);
847+
}
848+
}
849+
850+
// Now run through all the actual joints, looking for welds.
851+
for (auto joint_index : link.joints()) {
852+
const Joint& joint = joint_by_index(joint_index);
853+
if (joint.traits_index() != weld_joint_traits_index()) continue;
854+
const LinkIndex welded_link_index = joint.other_link_index(link_index);
855+
// Don't reprocess if we already did the other end.
856+
if (!result->contains(welded_link_index))
857+
AppendLinksWeldedTo(welded_link_index, &*result);
858+
}
859+
}
860+
861+
void LinkJointGraph::ThrowIfForestNotBuiltYet(const char* func) const {
862+
if (!forest_is_valid()) {
863+
throw std::logic_error(
864+
fmt::format("{}(): no SpanningForest available. Call BuildForest() "
865+
"before calling this function.",
866+
func));
867+
}
868+
}
869+
707870
void LinkJointGraph::ThrowLinkWasRemoved(const char* func,
708871
LinkIndex link_index) const {
709872
throw std::logic_error(fmt::format(

multibody/topology/link_joint_graph.h

+89-2
Original file line numberDiff line numberDiff line change
@@ -417,11 +417,11 @@ class LinkJointGraph {
417417
[[nodiscard]] inline const LoopConstraint& loop_constraints(
418418
LoopConstraintIndex constraint_index) const;
419419

420-
/** Links with this index or higher are "ephemeral" (added during
420+
/** Links with this ordinal or higher are "ephemeral" (added during
421421
forest-building). See the class comment for more information. */
422422
[[nodiscard]] int num_user_links() const { return data_.num_user_links; }
423423

424-
/** Joints with this index or higher are "ephemeral" (added during
424+
/** Joints with this ordinal or higher are "ephemeral" (added during
425425
forest-building). See the class comment for more information. */
426426
[[nodiscard]] int num_user_joints() const { return data_.num_user_joints; }
427427

@@ -509,6 +509,86 @@ class LinkJointGraph {
509509
void ChangeJointType(JointIndex existing_joint_index,
510510
const std::string& name_of_new_type);
511511

512+
/** After the Forest is built, returns the sequence of Links from World to the
513+
given Link L in the Forest. In case the Forest was built with a single Mobod
514+
for each Link Composite (Links connected by Weld joints), we only report the
515+
"active Link" for each Link Composite so that there is only one Link returned
516+
for each level in Link L's tree. World is always the active Link for its
517+
composite so will always be the first entry in the result. However, if L is
518+
part of a Link Composite the final entry will be L's composite's active link,
519+
which might not be L. Cost is O(ℓ) where ℓ is Link L's level in the
520+
SpanningForest.
521+
@@throws std::exception if the SpanningForest hasn't been built yet.
522+
@see link_composites(), SpanningForest::FindPathFromWorld() */
523+
std::vector<LinkIndex> FindPathFromWorld(LinkIndex link_index) const;
524+
525+
/** After the Forest is built, finds the first Link common to the paths
526+
towards World from each of two Links in the SpanningForest. Returns World
527+
immediately if the Links are on different trees of the forest. Otherwise the
528+
cost is O(ℓ) where ℓ is the length of the longer path from one of the Links
529+
to the ancestor.
530+
@throws std::exception if the SpanningForest hasn't been built yet.
531+
@see SpanningForest::FindFirstCommonAncestor()
532+
@see SpanningForest::FindPathsToFirstCommonAncestor() */
533+
LinkIndex FindFirstCommonAncestor(LinkIndex link1_index,
534+
LinkIndex link2_index) const;
535+
536+
/** After the Forest is built, finds all the Links following the Forest
537+
subtree whose root mobilized body is the one followed by the given Link. That
538+
is, we look up the given Link's Mobod B and return all the Links that follow
539+
B or any other Mobod in the subtree rooted at B. The Links following B
540+
come first, and the rest follow the depth-first ordering of the Mobods.
541+
In particular, the result is _not_ sorted by LinkIndex. Computational cost
542+
is O(ℓ) where ℓ is the number of Links following the subtree.
543+
@throws std::exception if the SpanningForest hasn't been built yet.
544+
@see SpanningForest::FindSubtreeLinks() */
545+
std::vector<LinkIndex> FindSubtreeLinks(LinkIndex link_index) const;
546+
547+
/** After the Forest is built, this method can be called to return a
548+
partitioning of the LinkJointGraph into subgraphs such that (a) every Link is
549+
in one and only one subgraph, and (b) two Links are in the same subgraph iff
550+
there is a path between them which consists only of Weld joints.
551+
Each subgraph of welded Links is represented as a set of
552+
Link indexes (using LinkIndex). By definition, these subgraphs will be
553+
disconnected by any non-Weld joint between two Links. A few notes:
554+
- The maximum number of returned subgraphs equals the number of Links in
555+
the graph. This corresponds to a graph with no Weld joints.
556+
- The World Link is included in a set of welded Links, and this set is
557+
element zero in the returned vector. The other subgraphs are in no
558+
particular order.
559+
- The minimum number of subgraphs is one. This corresponds to a graph with
560+
all Links welded to World.
561+
562+
@throws std::exception if the SpanningForest hasn't been built yet.
563+
@see CalcSubgraphsOfWeldedLinks() if you haven't built a Forest yet */
564+
std::vector<std::set<LinkIndex>> GetSubgraphsOfWeldedLinks() const;
565+
566+
/** This much-slower method does not depend on the SpanningForest having
567+
already been built. It is a fallback for when there is no Forest.
568+
@see GetSubgraphsOfWeldedLinks() if you already have a Forest built */
569+
std::vector<std::set<LinkIndex>> CalcSubgraphsOfWeldedLinks() const;
570+
571+
/** After the Forest is built, returns all Links that are transitively welded,
572+
or rigidly affixed, to `link_index`, per these two definitions:
573+
1. A Link is always considered welded to itself.
574+
2. Two unique Links are considered welded together exclusively by the
575+
presence of weld joints, not by other constructs such as constraints.
576+
577+
Therefore, if `link_index` is a valid index to a Link in this graph, then the
578+
return vector will always contain at least one entry storing `link_index`.
579+
This is fast because we just need to sort the already-calculated
580+
LinkComposite the given `link_index` is part of (if any).
581+
582+
@throws std::exception if the SpanningForest hasn't been built yet or
583+
`link_index` is out of range
584+
@see CalcLinksWeldedTo() if you haven't built a Forest yet */
585+
std::set<LinkIndex> GetLinksWeldedTo(LinkIndex link_index) const;
586+
587+
/** This slower method does not depend on the SpanningForest having
588+
already been built. It is a fallback for when there is no Forest.
589+
@see GetLinksWeldedTo() if you already have a Forest built */
590+
std::set<LinkIndex> CalcLinksWeldedTo(LinkIndex link_index) const;
591+
512592
// FYI Debugging APIs (including Graphviz-related) are defined in
513593
// link_joint_graph_debug.cc.
514594

@@ -518,6 +598,7 @@ class LinkJointGraph {
518598
The result is in the "dot" language, see https://graphviz.org. If you
519599
write it to some file foo.dot, you can generate a viewable png (for
520600
example) using the command `dot -Tpng foo.dot >foo.png`.
601+
@see SpanningForest::GenerateGraphvizString()
521602
@see MakeGraphvizFiles() for an easier way to get pngs. */
522603
std::string GenerateGraphvizString(
523604
std::string_view label, bool include_ephemeral_elements = true) const;
@@ -700,6 +781,12 @@ class LinkJointGraph {
700781
void AddUnmodeledJointToComposite(JointOrdinal unmodeled_joint_ordinal,
701782
LinkCompositeIndex which);
702783

784+
// This is the implementation for CalcLinksWeldedTo().
785+
void AppendLinksWeldedTo(LinkIndex link_index,
786+
std::set<LinkIndex>* result) const;
787+
788+
void ThrowIfForestNotBuiltYet(const char* func) const;
789+
703790
[[noreturn]] void ThrowLinkWasRemoved(const char* func,
704791
LinkIndex link_index) const;
705792

multibody/topology/spanning_forest.cc

+93
Original file line numberDiff line numberDiff line change
@@ -1008,6 +1008,99 @@ void SpanningForest::GrowCompositeMobod(
10081008
}
10091009
}
10101010

1011+
std::vector<MobodIndex> SpanningForest::FindPathFromWorld(
1012+
MobodIndex index) const {
1013+
const Mobod* mobod = &mobods(index);
1014+
std::vector<MobodIndex> path(mobod->level() + 1);
1015+
while (mobod->inboard().is_valid()) {
1016+
path[mobod->level()] = mobod->index();
1017+
mobod = &mobods(mobod->inboard());
1018+
}
1019+
DRAKE_DEMAND(mobod->is_world());
1020+
path[0] = MobodIndex(0);
1021+
return path;
1022+
}
1023+
1024+
MobodIndex SpanningForest::FindFirstCommonAncestor(
1025+
MobodIndex mobod1_index, MobodIndex mobod2_index) const {
1026+
// A body is its own first common ancestor.
1027+
if (mobod1_index == mobod2_index) return mobod1_index;
1028+
1029+
// If either body is World, that's the first common ancestor.
1030+
if (mobod1_index == world_mobod_index() ||
1031+
mobod2_index == world_mobod_index()) {
1032+
return world_mobod_index();
1033+
}
1034+
1035+
const Mobod* branch1 = &mobods(mobod1_index);
1036+
const Mobod* branch2 = &mobods(mobod2_index);
1037+
1038+
// If they are in different trees, World is the ancestor.
1039+
if (branch1->tree() != branch2->tree()) return world_mobod().index();
1040+
1041+
// Get down to a common level, then go down both branches.
1042+
while (branch1->level() > branch2->level())
1043+
branch1 = &mobods(branch1->inboard());
1044+
while (branch2->level() > branch1->level())
1045+
branch2 = &mobods(branch2->inboard());
1046+
1047+
// Both branches are at the same level now.
1048+
while (branch1->index() != branch2->index()) {
1049+
branch1 = &mobods(branch1->inboard());
1050+
branch2 = &mobods(branch2->inboard());
1051+
}
1052+
1053+
return branch1->index(); // Same as branch2->index().
1054+
}
1055+
1056+
MobodIndex SpanningForest::FindPathsToFirstCommonAncestor(
1057+
MobodIndex mobod1_index, MobodIndex mobod2_index,
1058+
std::vector<MobodIndex>* path1, std::vector<MobodIndex>* path2) const {
1059+
DRAKE_DEMAND(path1 != nullptr && path2 != nullptr);
1060+
path1->clear();
1061+
path2->clear();
1062+
// A body is its own first common ancestor.
1063+
if (mobod1_index == mobod2_index) return mobod1_index;
1064+
1065+
const Mobod* branch1 = &mobods(mobod1_index);
1066+
const Mobod* branch2 = &mobods(mobod2_index);
1067+
1068+
// Get down to a common level, then go down both branches.
1069+
while (branch1->level() > branch2->level()) {
1070+
path1->push_back(branch1->index());
1071+
branch1 = &mobods(branch1->inboard());
1072+
}
1073+
while (branch2->level() > branch1->level()) {
1074+
path2->push_back(branch2->index());
1075+
branch2 = &mobods(branch2->inboard());
1076+
}
1077+
1078+
// Both branches are at the same level now.
1079+
while (branch1->index() != branch2->index()) {
1080+
path1->push_back(branch1->index());
1081+
path2->push_back(branch2->index());
1082+
branch1 = &mobods(branch1->inboard());
1083+
branch2 = &mobods(branch2->inboard());
1084+
}
1085+
1086+
return branch1->index(); // Same as branch2->index().
1087+
}
1088+
1089+
std::vector<LinkIndex> SpanningForest::FindSubtreeLinks(
1090+
MobodIndex root_mobod_index) const {
1091+
const int num_subtree_mobods = mobods(root_mobod_index).num_subtree_mobods();
1092+
std::vector<LinkIndex> result;
1093+
result.reserve(num_subtree_mobods); // Will be at least this big.
1094+
for (int i = 0; i < num_subtree_mobods; ++i) {
1095+
const Mobod& subtree_mobod = mobods(MobodIndex(root_mobod_index + i));
1096+
for (LinkOrdinal ordinal : subtree_mobod.follower_link_ordinals()) {
1097+
const Link& link = links(ordinal);
1098+
result.push_back(link.index());
1099+
}
1100+
}
1101+
return result;
1102+
}
1103+
10111104
SpanningForest::Data::Data() = default;
10121105
SpanningForest::Data::Data(const Data&) = default;
10131106
SpanningForest::Data::Data(Data&&) = default;

0 commit comments

Comments
 (0)