Skip to content

Commit

Permalink
Bind DeformableModel::AddFixedConstraint (RobotLocomotion#21930)
Browse files Browse the repository at this point in the history
  • Loading branch information
xuchenhan-tri authored Sep 20, 2024
1 parent c90ff5d commit 1a680ab
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 0 deletions.
3 changes: 3 additions & 0 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1697,6 +1697,9 @@ PYBIND11_MODULE(plant, m) {
.def("SetWallBoundaryCondition", &Class::SetWallBoundaryCondition,
py::arg("id"), py::arg("p_WQ"), py::arg("n_W"),
cls_doc.SetWallBoundaryCondition.doc)
.def("AddFixedConstraint", &Class::AddFixedConstraint,
py::arg("body_A_id"), py::arg("body_B"), py::arg("X_BA"),
py::arg("shape"), py::arg("X_BG"), cls_doc.AddFixedConstraint.doc)
.def("GetDiscreteStateIndex", &Class::GetDiscreteStateIndex,
py::arg("id"), cls_doc.GetDiscreteStateIndex.doc)
.def("GetReferencePositions", &Class::GetReferencePositions,
Expand Down
7 changes: 7 additions & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -3351,6 +3351,13 @@ def test_deformable_model(self):
self.assertEqual(dut.GetBodyId(geometry_id), body_id)
dut.SetWallBoundaryCondition(body_id, [1, 1, -1], [0, 0, 1])

spatial_inertia = SpatialInertia_[float].SolidCubeWithDensity(1, 1)
rigid_body = plant.AddRigidBody("rigid_body", spatial_inertia)
dut.AddFixedConstraint(body_A_id=body_id,
body_B=rigid_body,
X_BA=RigidTransform(), shape=Box(1, 1, 1),
X_BG=RigidTransform())

# Verify that a body has been added to the model.
self.assertEqual(dut.num_bodies(), 1)
self.assertIsInstance(dut.GetReferencePositions(body_id), np.ndarray)
Expand Down

0 comments on commit 1a680ab

Please sign in to comment.