Skip to content

Commit

Permalink
multibody: add binding for GetFloatingBaseBodies (#14139)
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake authored Sep 28, 2020
1 parent dba012d commit e7112e6
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 0 deletions.
2 changes: 2 additions & 0 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -699,6 +699,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
py::arg("coulomb_friction"),
cls_doc.RegisterCollisionGeometry
.doc_5args_body_X_BG_shape_name_coulomb_friction)
.def("GetFloatingBaseBodies", &Class::GetFloatingBaseBodies,
cls_doc.GetFloatingBaseBodies.doc)
.def("get_source_id", &Class::get_source_id, cls_doc.get_source_id.doc)
.def("get_geometry_query_input_port",
&Class::get_geometry_query_input_port, py_rvp::reference_internal,
Expand Down
3 changes: 3 additions & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -616,6 +616,9 @@ def test_multibody_tree_kinematics(self, T):
X_WL = plant.CalcRelativeTransform(
context, frame_A=world_frame, frame_B=base_frame)
self.assertIsInstance(X_WL, RigidTransform)
free_bodies = plant.GetFloatingBaseBodies()
self.assertEqual(len(free_bodies), 1)
self.assertTrue(base.index() in free_bodies)

p_AQi = plant.CalcPointsPositions(
context=context, frame_B=base_frame,
Expand Down

0 comments on commit e7112e6

Please sign in to comment.