27
27
#include " drake/multibody/plant/hydroelastic_traction_calculator.h"
28
28
#include " drake/multibody/plant/make_discrete_update_manager.h"
29
29
#include " drake/multibody/plant/slicing_and_indexing.h"
30
+ #include " drake/multibody/topology/graph.h"
30
31
#include " drake/multibody/tree/door_hinge.h"
31
32
#include " drake/multibody/tree/prismatic_joint.h"
32
33
#include " drake/multibody/tree/prismatic_spring.h"
@@ -1053,8 +1054,10 @@ const SceneGraphInspector<T>& MultibodyPlant<T>::EvalSceneGraphInspector(
1053
1054
template <typename T>
1054
1055
std::vector<const RigidBody<T>*> MultibodyPlant<T>::GetBodiesWeldedTo(
1055
1056
const RigidBody<T>& body) const {
1057
+ const internal::LinkJointGraph& graph = internal_tree ().graph ();
1056
1058
const std::set<BodyIndex> island =
1057
- internal_tree ().multibody_graph ().FindBodiesWeldedTo (body.index ());
1059
+ graph.forest_is_valid () ? graph.GetLinksWeldedTo (body.index ())
1060
+ : graph.CalcLinksWeldedTo (body.index ());
1058
1061
// Map body indices to pointers.
1059
1062
std::vector<const RigidBody<T>*> sub_graph_bodies;
1060
1063
for (BodyIndex body_index : island) {
@@ -1079,7 +1082,10 @@ std::vector<BodyIndex> MultibodyPlant<T>::GetBodiesKinematicallyAffectedBy(
1079
1082
fmt::format (" {}: joint with index {} is welded." , __func__, joint));
1080
1083
}
1081
1084
}
1082
- return internal_tree ().GetBodiesKinematicallyAffectedBy (joint_indexes);
1085
+ const std::set<BodyIndex> links =
1086
+ internal_tree ().GetBodiesKinematicallyAffectedBy (joint_indexes);
1087
+ // TODO(sherm1) Change the return type to set to avoid this copy.
1088
+ return std::vector<BodyIndex>(links.cbegin (), links.cend ());
1083
1089
}
1084
1090
1085
1091
template <typename T>
@@ -1157,7 +1163,10 @@ void MultibodyPlant<T>::SetFreeBodyPoseInAnchoredFrame(
1157
1163
DRAKE_MBP_THROW_IF_NOT_FINALIZED ();
1158
1164
this ->ValidateContext (context);
1159
1165
1160
- if (!internal_tree ().get_topology ().IsBodyAnchored (frame_F.body ().index ())) {
1166
+ if (!internal_tree ()
1167
+ .graph ()
1168
+ .link_by_index (frame_F.body ().index ())
1169
+ .is_anchored ()) {
1161
1170
throw std::logic_error (" Frame '" + frame_F.name () +
1162
1171
" ' must be anchored to the world frame." );
1163
1172
}
@@ -1262,6 +1271,7 @@ void MultibodyPlant<T>::Finalize() {
1262
1271
if (geometry_source_is_registered ()) {
1263
1272
ApplyDefaultCollisionFilters ();
1264
1273
}
1274
+
1265
1275
FinalizePlantOnly ();
1266
1276
1267
1277
// Make the manager of discrete updates.
@@ -1527,7 +1537,7 @@ void MultibodyPlant<T>::ApplyDefaultCollisionFilters() {
1527
1537
}
1528
1538
// We explicitly exclude collisions within welded subgraphs.
1529
1539
std::vector<std::set<BodyIndex>> subgraphs =
1530
- internal_tree ().multibody_graph ().FindSubgraphsOfWeldedBodies ();
1540
+ internal_tree ().graph ().GetSubgraphsOfWeldedLinks ();
1531
1541
for (const auto & subgraph : subgraphs) {
1532
1542
// Only operate on non-trivial weld subgraphs.
1533
1543
if (subgraph.size () <= 1 ) {
@@ -3899,24 +3909,23 @@ void MultibodyPlant<T>::CalcReactionForces(
3899
3909
// Since vdot is the result of Fapplied and tau_applied we expect the result
3900
3910
// from inverse dynamics to be zero.
3901
3911
// TODO(amcastro-tri): find a better estimation for this bound. For instance,
3902
- // we can make an estimation based on the trace of the mass matrix (Jain 2011,
3903
- // Eq. 4.21). For now we only ASSERT though with a better estimation we could
3904
- // promote this to a DEMAND.
3912
+ // we can make an estimation based on the trace of the mass matrix (Jain
3913
+ // 2011, Eq. 4.21). For now we only ASSERT though with a better estimation
3914
+ // we could romote this to a DEMAND.
3905
3915
// TODO(amcastro-tri) Uncomment this line once issue #12473 is resolved.
3906
- // DRAKE_ASSERT(tau_id.norm() <
3907
- // 100 * num_velocities() *
3908
- // std::numeric_limits<double>::epsilon());
3916
+ // DRAKE_ASSERT(tau_id.norm() <
3917
+ // 100 * num_velocities() *
3918
+ // std::numeric_limits<double>::epsilon());
3909
3919
3910
3920
// Map mobilizer reaction forces to joint reaction forces and perform the
3911
3921
// necessary frame conversions.
3912
3922
for (JointIndex joint_index : GetJointIndices ()) {
3913
3923
const Joint<T>& joint = get_joint (joint_index);
3914
- const internal::MobilizerIndex mobilizer_index =
3924
+ const internal::MobodIndex mobilizer_index =
3915
3925
internal_tree ().get_joint_mobilizer (joint_index);
3916
3926
const internal::Mobilizer<T>& mobilizer =
3917
3927
internal_tree ().get_mobilizer (mobilizer_index);
3918
- const internal::MobodIndex mobod_index =
3919
- mobilizer.get_topology ().mobod_index ;
3928
+ const internal::MobodIndex mobod_index = mobilizer.mobod ().index ();
3920
3929
3921
3930
// Force on mobilized body B at mobilized frame's origin Mo, expressed in
3922
3931
// world frame.
@@ -4051,7 +4060,7 @@ void MultibodyPlant<T>::RemoveUnsupportedScalars(
4051
4060
template <typename T>
4052
4061
std::vector<std::set<BodyIndex>>
4053
4062
MultibodyPlant<T>::FindSubgraphsOfWeldedBodies() const {
4054
- return internal_tree ().multibody_graph ().FindSubgraphsOfWeldedBodies ();
4063
+ return internal_tree ().graph ().GetSubgraphsOfWeldedLinks ();
4055
4064
}
4056
4065
4057
4066
template <typename T>
0 commit comments