dair_pll.multibody_learnable_system
Construction and analysis of learnable multibody systems.
Similar to Drake, multibody systems are instantiated as a child class of
System
: MultibodyLearnableSystem
. This object is a thin
wrapper for a MultibodyTerms
member variable, which manages
computation of lumped terms necessary for simulation and evaluation.
Simulation is implemented via Anitescu’s [1] convex method.
An interface for the ContactNets [2] loss is also defined as an alternative to prediction loss.
A large portion of the internal implementation of DrakeSystem
is
implemented in MultibodyPlantDiagram
.
[1] M. Anitescu, “Optimization-based simulation of nonsmooth rigid multibody dynamics,” Mathematical Programming, 2006, https://doi.org/10.1007/s10107-005-0590-7 [2] S. Pfrommer*, M. Halm*, and M. Posa. “ContactNets: Learning Discontinuous Contact Dynamics with Smooth, Implicit Representations,” Conference on Robotic Learning, 2020, https://proceedings.mlr.press/v155/pfrommer21a.html
- class dair_pll.multibody_learnable_system.MultibodyLearnableSystem(init_urdfs, dt, output_urdfs_dir=None)[source]
Bases:
System
System
interface for dynamics associated withMultibodyTerms
.Inits
MultibodyLearnableSystem
with provided model URDFs.Implementation is primarily based on Drake. Bodies are modeled via
MultibodyTerms
, which uses Drake symbolics to generate dynamics terms, and the system can be exported back to a Drake-interpretable representation as a set of URDFs.- Parameters:
-
multibody_terms:
dair_pll.multibody_terms.MultibodyTerms
-
init_urdfs:
typing.Dict
[str
,str
]
-
output_urdfs_dir:
typing.Optional
[str
] = None
-
visualization_system:
typing.Optional
[dair_pll.drake_system.DrakeSystem
]
-
solver:
sappy.sap.SAPSolver
- contactnets_loss(x, u, x_plus, loss_pool=None)[source]
Calculate ContactNets [1] loss for state transition.
References
[1] S. Pfrommer*, M. Halm*, and M. Posa. “ContactNets: Learning Discontinuous Contact Dynamics with Smooth, Implicit Representations,” Conference on Robotic Learning, 2020, https://proceedings.mlr.press/v155/pfrommer21a.html
- forward_dynamics(q, v, u, dynamics_pool=None)[source]
Calculates delta velocity from current state and input.
Implement’s Anitescu’s [1] convex formulation in dual form, derived similarly to Tedrake [2] and described here.
Let v_minus be the contact-free next velocity, i.e.:
v + dt * non_contact_acceleration.
Let FC be the combined friction cone:
FC = {[beta_n beta_t]: beta_n_i >= ||beta_t_i||}.
The primal version of Anitescu’s formulation is as follows:
min_{v_plus,s} (v_plus - v_minus)^T M(q)(v_plus - v_minus)/2 s.t. s = [I; 0]phi(q)/dt + J(q)v_plus, s \\in FC.
The KKT conditions are the mixed cone complementarity problem [3, Theorem 2]:
s = [I; 0]phi(q)/dt + J(q)v_plus, M(q)(v_plus - v_minus) = J(q)^T f, FC \\ni s \\perp f \\in FC.
As M(q) is positive definite, we can solve for v_plus in terms of lambda, and thus these conditions can be simplified to:
FC \\ni D(q)f + J(q)v_minus + [I;0]phi(q)/dt \\perp f \\in FC.
which in turn are the KKT conditions for the dual QCQP we solve:
min_{f} f^T D(q) f/2 + f^T(J(q)v_minus + [I;0]phi(q)/dt) s.t. f \\in FC.
References
[1] M. Anitescu, “Optimization-based simulation of nonsmooth rigid multibody dynamics,” Mathematical Programming, 2006, https://doi.org/10.1007/s10107-005-0590-7 [2] R. Tedrake. Underactuated Robotics: Algorithms for Walking, Running, Swimming, Flying, and Manipulation (Course Notes for MIT 6.832), https://underactuated.mit.edu [3] S. Z. N’emeth, G. Zhang, “Conic optimization and complementarity problems,” arXiv, https://doi.org/10.48550/arXiv.1607.05161
- Parameters:
- Return type:
- Returns:
(*, space.n_v) delta velocity batch.
- sim_step(x, carry)[source]
Integrator.partial_step
wrapper forforward_dynamics()
.
- summary(statistics)[source]
Generates summary statistics for multibody system.
The scalars returned are simply the scalar description of the system’s
MultibodyTerms
.Meshes are generated for learned
DeepSupportConvex
es.- Parameters:
statistics (
Dict
) – Updated evaluation statistics for the model.- Return type:
- Returns:
Scalars and meshes packaged into a
SystemSummary
.