How do I take gradients of MultibodyPlant computations w.r.t. mass, center-of-mass, inertia, etc.?

70 views Asked by At

I see the current chapter of Underactuated: System Identification and the corresponding notebook, and it currently does it through symbolics.

I'd like to try out stuff like system identification using forward-mode automatic differentiation ("autodiff" via AutoDiffXd, etc.), just to check things like scalability, get a better feel for symbolics and autodiff options in Drake, etc.

As a first steps towards system identification with autodiff, how do I take gradients of MultibodyPlant quantities (e.g. generalized forces, forward dynamics, etc.) with respect to inertial parameters (say mass)?


1

There are 1 answers

0
Eric Cousineau On BEST ANSWER

Drake's formulation of MultibodyPlant, in conjunction with the Drake Systems framework, can allow you to take derivatives (via autodiff) with respect to inertial parameters by using the parameter accessors of RigidBody<T> on the given plant's Context<AutoDiffXd>.

Please see the following tutorial:
https://nbviewer.jupyter.org/github/RobotLocomotion/drake/blob/nightly-release/tutorials/multibody_plant_autodiff_mass.ipynb