Skip to content

Commit

Permalink
Add bindings for MultibodyPlant::CalcGeneralizedForce() (#20102)
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake and jwnimmer-tri authored Aug 31, 2023
1 parent ef98b12 commit 09752cc
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 2 deletions.
10 changes: 10 additions & 0 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -637,6 +637,16 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def("CalcGravityGeneralizedForces",
&Class::CalcGravityGeneralizedForces, py::arg("context"),
cls_doc.CalcGravityGeneralizedForces.doc)
.def(
"CalcGeneralizedForces",
[](const Class* self, const Context<T>& context,
const MultibodyForces<T>& forces) {
VectorX<T> tau(self->num_velocities());
self->CalcGeneralizedForces(context, forces, &tau);
return tau;
},
py::arg("context"), py::arg("forces"),
cls_doc.CalcGeneralizedForces.doc)
.def("MakeActuationMatrix", &Class::MakeActuationMatrix,
cls_doc.MakeActuationMatrix.doc)
.def(
Expand Down
4 changes: 4 additions & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -2542,6 +2542,8 @@ def test_multibody_dynamics(self, T):

forces = MultibodyForces(plant=plant)
plant.CalcForceElementsContribution(context=context, forces=forces)
tau = plant.CalcGeneralizedForces(context=context, forces=forces)
self.assertEqual(tau.shape, (2,))
copy.copy(forces)

# Test generalized forces.
Expand All @@ -2552,6 +2554,8 @@ def test_multibody_dynamics(self, T):
np.testing.assert_equal(forces.generalized_forces(), 1)
forces.SetZero()
np.testing.assert_equal(forces.generalized_forces(), 0)
tau = plant.CalcGeneralizedForces(context=context, forces=forces)
np.testing.assert_equal(tau, [0, 0])

# Test standalone construction.
standalone_forces = MultibodyForces(nb=1, nv=2)
Expand Down
6 changes: 4 additions & 2 deletions multibody/tree/multibody_forces.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@ template <typename T> class MultibodyTree;
template <typename T> class MultibodyTreeSystem;
} // namespace internal

/// A class to hold a set of forces applied to a MultibodyTree system.
/// Forces can include generalized forces as well as body spatial forces.
/// A class to hold a set of forces applied to a MultibodyTree system. Forces
/// can include generalized forces as well as body spatial forces.
/// MultibodyPlant::CalcGeneralizedForces() can be used to compute the _total_
/// generalized force, combining generalized_forces() and body_forces().
///
/// @tparam_default_scalar
template <typename T>
Expand Down

0 comments on commit 09752cc

Please sign in to comment.