@@ -631,18 +631,17 @@ void DeformableDriver<T>::AppendDeformableRigidFixedConstraintKinematics(
631
631
.template Eval <geometry::GeometryConfigurationVector<T>>(context);
632
632
for (DeformableBodyIndex index (0 ); index < deformable_model_->num_bodies ();
633
633
++index) {
634
- DeformableBodyId body_id = deformable_model_->GetBodyId (index);
635
- if (!deformable_model_->is_enabled (body_id, context) ||
636
- !deformable_model_->HasConstraint (body_id)) {
634
+ const DeformableBody<T>& body = deformable_model_->GetBody (index);
635
+ if (!body.is_enabled (context) || !body.has_fixed_constraint ()) {
637
636
continue ;
638
637
}
639
638
640
- const FemModel<T>& fem_model = deformable_model_-> GetFemModel (body_id );
639
+ const FemModel<T>& fem_model = body. fem_model ( );
641
640
const DirichletBoundaryCondition<T>& bc =
642
641
fem_model.dirichlet_boundary_condition ();
643
642
644
- /* Returns true iff for the deformable body with `body_id` , the given vertex
645
- index is under boundary condition. */
643
+ /* Returns true iff for the deformable body, the given vertex index is under
644
+ boundary condition. */
646
645
auto is_under_bc = [&](int vertex_index) {
647
646
return bc.index_to_boundary_state ().count (
648
647
multibody::fem::FemNodeIndex (vertex_index)) > 0 ;
@@ -653,15 +652,13 @@ void DeformableDriver<T>::AppendDeformableRigidFixedConstraintKinematics(
653
652
// Each deformable body forms its own clique and are indexed in inceasing
654
653
// DeformableBodyIndex order and placed after all rigid cliques.
655
654
const TreeIndex clique_index_A (tree_topology.num_trees () + index);
656
- GeometryId geometry_id = deformable_model_-> GetGeometryId (body_id );
655
+ const GeometryId geometry_id = body. geometry_id ( );
657
656
const PartialPermutation& vertex_permutation =
658
657
EvalVertexPermutation (context, geometry_id);
659
658
const VectorX<T>& p_WVs = configurations.value (geometry_id);
660
659
661
- for (const MultibodyConstraintId& constraint_id :
662
- deformable_model_->fixed_constraint_ids (body_id)) {
663
- const DeformableRigidFixedConstraintSpec& spec =
664
- deformable_model_->fixed_constraint_spec (constraint_id);
660
+ for (const DeformableRigidFixedConstraintSpec& spec :
661
+ body.fixed_constraint_specs ()) {
665
662
const int num_vertices_in_constraint = ssize (spec.vertices );
666
663
/* The Jacobian block for the deformable body A. */
667
664
Block3x3SparseMatrix<T> negative_Jv_v_WAp (
@@ -1056,23 +1053,21 @@ void DeformableDriver<T>::CalcDeformableContact(
1056
1053
/* Complete the result with information on constraints other than contact. */
1057
1054
for (DeformableBodyIndex body_index (0 );
1058
1055
body_index < deformable_model_->num_bodies (); ++body_index) {
1059
- DeformableBodyId body_id = deformable_model_->GetBodyId (body_index);
1056
+ const DeformableBody<T>& body = deformable_model_->GetBody (body_index);
1060
1057
/* Add in constraints. */
1061
- if (deformable_model_-> HasConstraint (body_id )) {
1058
+ if (body. has_fixed_constraint ( )) {
1062
1059
std::unordered_set<int > fixed_vertices;
1063
- for (const MultibodyConstraintId& constraint_id :
1064
- deformable_model_->fixed_constraint_ids (body_id)) {
1065
- const DeformableRigidFixedConstraintSpec& spec =
1066
- deformable_model_->fixed_constraint_spec (constraint_id);
1060
+ for (const DeformableRigidFixedConstraintSpec& spec :
1061
+ body.fixed_constraint_specs ()) {
1067
1062
fixed_vertices.insert (spec.vertices .begin (), spec.vertices .end ());
1068
1063
}
1069
1064
/* Register the geometry in case it hasn't been registered because it's
1070
1065
not participating in contact but is participating in other types of
1071
1066
constraints. */
1072
- GeometryId geometry_id = deformable_model_-> GetGeometryId (body_id );
1067
+ GeometryId geometry_id = body. geometry_id ( );
1073
1068
if (!result->IsRegistered (geometry_id)) {
1074
- result->RegisterDeformableGeometry (
1075
- geometry_id, deformable_model_-> GetFemModel (body_id ).num_nodes ());
1069
+ result->RegisterDeformableGeometry (geometry_id,
1070
+ body. fem_model ( ).num_nodes ());
1076
1071
}
1077
1072
result->Participate (geometry_id, fixed_vertices);
1078
1073
}
0 commit comments