pydrake.multibody.cenic

class pydrake.multibody.cenic.CenicIntegrator

Bases: pydrake.systems.analysis.IntegratorBase

Convex Error-controlled Numerical Integration for Contact (CENIC) is a specialized error-controlled implicit integrator for contact-rich robotics simulations [Kurtz and Castro, 2025].

CENIC provides variable-step error-controlled integration for multibody systems with stiff contact interactions, while maintaining the high speeds characteristic of discrete-time solvers required for modern robotics workflows.

Benefits of CENIC include:

  • Guaranteed convergence. Unlike traditional implicit integrators that rely

on non-convex Newton-Raphson solves, CENIC’s convex formulation eliminates step rejections due to convergence failures.

  • Guaranteed accuracy. CENIC inherits the well-studied accuracy guarantees

associated with error-controlled integration [Hairer and Wanner, 1996], avoiding discretization artifacts common in fixed-step discrete-time methods.

  • Automatic time step selection. Users specify a desired accuracy rather

than a fixed time step, eliminating a common pain point in authoring multibody simulations.

  • Implicit treatment of external systems. This means that users can connect

arbitrary stiff controllers (e.g., a custom LeafSystem) to the MultibodyPlant and have them treated implicitly in CENIC’s convex formulation. This allows for larger time steps, leading to faster and more stable simulations.

  • Principled static/dynamic friction modeling. Unlike discrete solvers,

CENIC can simulate frictional contact with different static and dynamic friction coefficients.

  • Speed. CENIC consistently outperforms general-purpose integrators by

orders of magnitude on contact-rich problems. Error-controlled CENIC is often (but not always) faster than discrete-time simulation, depending on the simulation in question and the requested accuracy.

CENIC works by solving a convex Irrotational Contact Fields (ICF) optimization problem [Castro et al., 2023] to advance the system state at each time step. A simple half-stepping strategy provides a second-order error estimate for automatic step-size selection.

Because CENIC is specific to multibody systems, the system it’s asked to integrate must either be a MultibodyPlant system or a Diagram that contains a MultibodyPlant subsystem, at any level of Diagram nesting.

Running CENIC in fixed-step mode (with error-control disabled) recovers the “Lagged” variant of discrete-time ICF simulation from [Castro et al., 2023].

Implementation notes:

Warning

CENIC’s error control implementation is not sensitive to continuous state of systems other than the plant(). See issue #23921.

Warning

When asked to perform 0-sized integration steps, CENIC executes a special case that does no integration or state updates, but does reset the error estimate to all 0, and always succeeds. This is in contrast to other integrator implementations in Drake. See DoStep() in the implementation.

References:

[Castro et al., 2023] Castro A., Han X., and Masterjohn J., 2023. Irrotational Contact Fields. https://arxiv.org/abs/2312.03908.

[Hairer and Wanner, 1996] Hairer E. and Wanner G., 1996. Solving Ordinary Differential Equations II: Stiff and Differential-Algebraic Problems. Springer Series in Computational Mathematics, Vol. 14. Springer-Verlag, Berlin, 2nd edition.

[Kurtz and Castro, 2025] Kurtz V. and Castro A., 2025. CENIC: Convex Error-controlled Numerical Integration for Contact. https://arxiv.org/abs/2511.08771.

Note

This class is templated; see CenicIntegrator_ for the list of instantiations.

__init__(self: pydrake.multibody.cenic.CenicIntegrator, system: pydrake.systems.framework.System, context: pydrake.systems.framework.Context = None) None

Constructs the integrator.

Parameter system:

The overall system to simulate. Must either be a MultibodyPlant or a Diagram that contains exactly one continuous-time MultibodyPlant. Other (discrete-time) plants are allowed in a diagram. This system is aliased by this object so must remain alive longer than the integrator.

Parameter context:

context for the overall system.

get_solver_parameters(self: pydrake.multibody.cenic.CenicIntegrator) pydrake.multibody.contact_solvers.IcfSolverParameters

Gets the current convex solver tolerances and iteration limits.

SetSolverParameters(self: pydrake.multibody.cenic.CenicIntegrator, parameters: pydrake.multibody.contact_solvers.IcfSolverParameters) None

Sets the convex solver tolerances and iteration limits.

template pydrake.multibody.cenic.CenicIntegrator_

Instantiations: CenicIntegrator_[float], CenicIntegrator_[AutoDiffXd]

class pydrake.multibody.cenic.CenicIntegrator_[AutoDiffXd]

Bases: pydrake.systems.analysis.IntegratorBase_[AutoDiffXd]

Convex Error-controlled Numerical Integration for Contact (CENIC) is a specialized error-controlled implicit integrator for contact-rich robotics simulations [Kurtz and Castro, 2025].

CENIC provides variable-step error-controlled integration for multibody systems with stiff contact interactions, while maintaining the high speeds characteristic of discrete-time solvers required for modern robotics workflows.

Benefits of CENIC include:

  • Guaranteed convergence. Unlike traditional implicit integrators that rely

on non-convex Newton-Raphson solves, CENIC’s convex formulation eliminates step rejections due to convergence failures.

  • Guaranteed accuracy. CENIC inherits the well-studied accuracy guarantees

associated with error-controlled integration [Hairer and Wanner, 1996], avoiding discretization artifacts common in fixed-step discrete-time methods.

  • Automatic time step selection. Users specify a desired accuracy rather

than a fixed time step, eliminating a common pain point in authoring multibody simulations.

  • Implicit treatment of external systems. This means that users can connect

arbitrary stiff controllers (e.g., a custom LeafSystem) to the MultibodyPlant and have them treated implicitly in CENIC’s convex formulation. This allows for larger time steps, leading to faster and more stable simulations.

  • Principled static/dynamic friction modeling. Unlike discrete solvers,

CENIC can simulate frictional contact with different static and dynamic friction coefficients.

  • Speed. CENIC consistently outperforms general-purpose integrators by

orders of magnitude on contact-rich problems. Error-controlled CENIC is often (but not always) faster than discrete-time simulation, depending on the simulation in question and the requested accuracy.

CENIC works by solving a convex Irrotational Contact Fields (ICF) optimization problem [Castro et al., 2023] to advance the system state at each time step. A simple half-stepping strategy provides a second-order error estimate for automatic step-size selection.

Because CENIC is specific to multibody systems, the system it’s asked to integrate must either be a MultibodyPlant system or a Diagram that contains a MultibodyPlant subsystem, at any level of Diagram nesting.

Running CENIC in fixed-step mode (with error-control disabled) recovers the “Lagged” variant of discrete-time ICF simulation from [Castro et al., 2023].

Implementation notes:

Warning

CENIC’s error control implementation is not sensitive to continuous state of systems other than the plant(). See issue #23921.

Warning

When asked to perform 0-sized integration steps, CENIC executes a special case that does no integration or state updates, but does reset the error estimate to all 0, and always succeeds. This is in contrast to other integrator implementations in Drake. See DoStep() in the implementation.

References:

[Castro et al., 2023] Castro A., Han X., and Masterjohn J., 2023. Irrotational Contact Fields. https://arxiv.org/abs/2312.03908.

[Hairer and Wanner, 1996] Hairer E. and Wanner G., 1996. Solving Ordinary Differential Equations II: Stiff and Differential-Algebraic Problems. Springer Series in Computational Mathematics, Vol. 14. Springer-Verlag, Berlin, 2nd edition.

[Kurtz and Castro, 2025] Kurtz V. and Castro A., 2025. CENIC: Convex Error-controlled Numerical Integration for Contact. https://arxiv.org/abs/2511.08771.

__init__(self: pydrake.multibody.cenic.CenicIntegrator_[AutoDiffXd], system: pydrake.systems.framework.System_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd] = None) None

Constructs the integrator.

Parameter system:

The overall system to simulate. Must either be a MultibodyPlant or a Diagram that contains exactly one continuous-time MultibodyPlant. Other (discrete-time) plants are allowed in a diagram. This system is aliased by this object so must remain alive longer than the integrator.

Parameter context:

context for the overall system.

get_solver_parameters(self: pydrake.multibody.cenic.CenicIntegrator_[AutoDiffXd]) pydrake.multibody.contact_solvers.IcfSolverParameters

Gets the current convex solver tolerances and iteration limits.

SetSolverParameters(self: pydrake.multibody.cenic.CenicIntegrator_[AutoDiffXd], parameters: pydrake.multibody.contact_solvers.IcfSolverParameters) None

Sets the convex solver tolerances and iteration limits.