Skip to content

Commit

Permalink
[multibody] Add binding for MultibodyPlant::GetActuationFromArray() (#…
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake authored Dec 28, 2024
1 parent 6848228 commit 30baad1
Show file tree
Hide file tree
Showing 2 changed files with 6 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 @@ -442,6 +442,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
cls_doc.SetDefaultFreeBodyPose.doc)
.def("GetDefaultFreeBodyPose", &Class::GetDefaultFreeBodyPose,
py::arg("body"), cls_doc.GetDefaultFreeBodyPose.doc)
.def("GetActuationFromArray", &Class::GetActuationFromArray,
py::arg("model_instance"), py::arg("u"),
cls_doc.GetActuationFromArray.doc)
.def("SetActuationInArray", &Class::SetActuationInArray,
py::arg("model_instance"), py::arg("u_instance"), py::arg("u"),
cls_doc.SetActuationInArray.doc)
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 @@ -1941,6 +1941,9 @@ def test_model_instance_state_access_by_array(self, T):
plant.SetActuationInArray(
model_instance=iiwa_model, u_instance=u_iiwa, u=u)
numpy_compare.assert_float_equal(u_iiwa, u[:7])
numpy_compare.assert_float_equal(
u_iiwa, plant.GetActuationFromArray(
model_instance=iiwa_model, u=u))

@numpy_compare.check_all_types
def test_map_qdot_to_v_and_back(self, T):
Expand Down

0 comments on commit 30baad1

Please sign in to comment.