Drake
ImplicitEulerIntegrator< T > Class Template Referencefinal

A first-order, fully implicit integrator with second order error estimation. More...

#include <drake/systems/analysis/implicit_euler_integrator.h>

Inheritance diagram for ImplicitEulerIntegrator< T >:
Collaboration diagram for ImplicitEulerIntegrator< T >:

Public Types

enum  JacobianComputationScheme { kForwardDifference, kCentralDifference, kAutomatic }
 Selecting the wrong such Jacobian determination scheme will slow (possibly critically) the implicit integration process. More...
 
- Public Types inherited from IntegratorBase< T >
enum  StepResult {
  kReachedPublishTime = 1, kReachedZeroCrossing = 2, kReachedUpdateTime = 3, kTimeHasAdvanced = 4,
  kReachedBoundaryTime = 5, kReachedStepLimit = 6
}
 Status returned by StepOnceAtMost(). More...
 

Public Member Functions

 ~ImplicitEulerIntegrator () override=default
 
 ImplicitEulerIntegrator (const System< T > &system, Context< T > *context=nullptr)
 
bool supports_error_estimation () const override
 The integrator supports error estimation. More...
 
int get_error_estimate_order () const override
 This integrator provides second order error estimates. More...
 
Does not allow copy, move, or assignment
 ImplicitEulerIntegrator (const ImplicitEulerIntegrator &)=delete
 
ImplicitEulerIntegratoroperator= (const ImplicitEulerIntegrator &)=delete
 
 ImplicitEulerIntegrator (ImplicitEulerIntegrator &&)=delete
 
ImplicitEulerIntegratoroperator= (ImplicitEulerIntegrator &&)=delete
 
Methods for getting and setting the Jacobian scheme.

Methods for getting and setting the scheme used to determine the Jacobian matrix necessary for solving the requisite nonlinear system if equations.

See also
JacobianComputationScheme
void set_reuse (bool reuse)
 Sets whether the integrator attempts to reuse Jacobian matrices and iteration matrix factorizations (default is true). More...
 
bool get_reuse () const
 Gets whether the integrator attempts to reuse Jacobian matrices and iteration matrix factorizations. More...
 
void set_jacobian_computation_scheme (JacobianComputationScheme scheme)
 Sets the Jacobian computation scheme. More...
 
JacobianComputationScheme get_jacobian_computation_scheme () const
 
Cumulative statistics functions.

The functions return statistics specific to the implicit integration process.

int64_t get_num_error_estimator_derivative_evaluations () const
 Gets the number of ODE function evaluations (calls to CalcTimeDerivatives()) used only for the error estimation process since the last call to ResetStatistics(). More...
 
int64_t get_num_derivative_evaluations_for_jacobian () const
 Gets the number of ODE function evaluations (calls to CalcTimeDerivatives()) used only for computing the Jacobian matrices since the last call to ResetStatistics(). More...
 
int64_t get_num_newton_raphson_iterations () const
 Gets the number of iterations used in the Newton-Raphson nonlinear systems of equation solving process since the last call to ResetStatistics(). More...
 
int64_t get_num_jacobian_evaluations () const
 Gets the number of Jacobian evaluations (i.e., the number of times that the Jacobian matrix was reformed) since the last call to ResetStatistics(). More...
 
int64_t get_num_iteration_matrix_factorizations () const
 Gets the number of factorizations of the iteration matrix since the last call to ResetStatistics(). More...
 
Error-estimation statistics functions.

The functions return statistics specific to the error estimation process.

Gets the number of ODE function evaluations (calls to CalcTimeDerivatives()) used only for computing the Jacobian matrices needed by the error estimation process since the last call to ResetStatistics().

int64_t get_num_error_estimator_derivative_evaluations_for_jacobian () const
 
int64_t get_num_error_estimator_newton_raphson_iterations () const
 Gets the number of iterations used in the Newton-Raphson nonlinear systems of equation solving process for the error estimation process since the last call to ResetStatistics(). More...
 
int64_t get_num_error_estimator_jacobian_evaluations () const
 Gets the number of Jacobian matrix evaluations used only during the error estimation process since the last call to ResetStatistics(). More...
 
int64_t get_num_error_estimator_iteration_matrix_factorizations () const
 Gets the number of factorizations of the iteration matrix used only during the error estimation process since the last call to ResetStatistics(). More...
 
- Public Member Functions inherited from IntegratorBase< T >
 IntegratorBase (const System< T > &system, Context< T > *context=nullptr)
 Maintains references to the system being integrated and the context used to specify the initial conditions for that system (if any). More...
 
virtual ~IntegratorBase ()=default
 Destructor. More...
 
void set_fixed_step_mode (bool flag)
 Sets an integrator with error control to fixed step mode. More...
 
bool get_fixed_step_mode () const
 Gets whether an integrator is running in fixed step mode. More...
 
void set_target_accuracy (double accuracy)
 Request that the integrator attempt to achieve a particular accuracy for the continuous portions of the simulation. More...
 
double get_target_accuracy () const
 Gets the target accuracy. More...
 
double get_accuracy_in_use () const
 Gets the accuracy in use by the integrator. More...
 
void set_maximum_step_size (const T &max_step_size)
 Sets the maximum step size that may be taken by this integrator. More...
 
const T & get_maximum_step_size () const
 Gets the maximum step size that may be taken by this integrator. More...
 
void Reset ()
 Resets the integrator to initial values, i.e., default construction values. More...
 
void Initialize ()
 An integrator must be initialized before being used. More...
 
void request_initial_step_size_target (const T &step_size)
 Request that the first attempted integration step have a particular size. More...
 
const T & get_initial_step_size_target () const
 Gets the target size of the first integration step. More...
 
StepResult IntegrateAtMost (const T &publish_dt, const T &update_dt, const T &boundary_dt)
 Integrates the system forward in time by a single step with step size subject to integration error tolerances (assuming that the integrator supports error estimation). More...
 
double get_stretch_factor () const
 Gets the stretch factor (> 1), which is multiplied by the maximum (typically user-designated) integration step size to obtain the amount that the integrator is able to stretch the maximum time step toward hitting an upcoming publish or update event in IntegrateAtMost(). More...
 
void IntegrateWithMultipleSteps (const T &dt)
 Stepping function for integrators operating outside of Simulator that advances the continuous state exactly by dt. More...
 
void IntegrateWithSingleFixedStep (const T &dt)
 Stepping function for integrators operating outside of Simulator that advances the continuous state exactly by dt and using a single fixed step. More...
 
const T & get_ideal_next_step_size () const
 Return the step size the integrator would like to take next, based primarily on the integrator's accuracy prediction. More...
 
const Context< T > & get_context () const
 Returns a const reference to the internally-maintained Context holding the most recent state in the trajectory. More...
 
Context< T > * get_mutable_context ()
 Returns a mutable pointer to the internally-maintained Context holding the most recent state in the trajectory. More...
 
void reset_context (Context< T > *context)
 Replace the pointer to the internally-maintained Context with a different one. More...
 
const System< T > & get_system () const
 Gets a constant reference to the system that is being integrated (and was provided to the constructor of the integrator). More...
 
bool is_initialized () const
 Indicates whether the integrator has been initialized. More...
 
const T & get_previous_integration_step_size () const
 Gets the size of the last (previous) integration step. More...
 
const ContinuousState< T > * get_error_estimate () const
 Gets the error estimate (used only for integrators that support error estimation). More...
 
 IntegratorBase (const IntegratorBase &)=delete
 
IntegratorBaseoperator= (const IntegratorBase &)=delete
 
 IntegratorBase (IntegratorBase &&)=delete
 
IntegratorBaseoperator= (IntegratorBase &&)=delete
 
void set_requested_minimum_step_size (const T &min_step_size)
 Sets the requested minimum step size h_min that may be taken by this integrator. More...
 
const T & get_requested_minimum_step_size () const
 Gets the requested minimum step size h_min for this integrator. More...
 
void set_throw_on_minimum_step_size_violation (bool throws)
 Sets whether the integrator should throw a std::runtime_error exception when the integrator's step size selection algorithm determines that it must take a step smaller than the minimum step size (for, e.g., purposes of error control). More...
 
bool get_throw_on_minimum_step_size_violation () const
 Reports the current setting of the throw_on_minimum_step_size_violation flag. More...
 
get_working_minimum_step_size () const
 Gets the current value of the working minimum step size h_work(t) for this integrator, which may vary with the current time t as stored in the integrator's context. More...
 
void ResetStatistics ()
 Forget accumulated statistics. More...
 
int64_t get_num_substep_failures () const
 Gets the number of failed sub-steps (implying one or more step size reductions was required to permit solving the necessary nonlinear system of equations). More...
 
int64_t get_num_step_shrinkages_from_substep_failures () const
 Gets the number of step size shrinkages due to sub-step failures (e.g., integrator convergence failures) since the last call to ResetStatistics() or Initialize(). More...
 
int64_t get_num_step_shrinkages_from_error_control () const
 Gets the number of step size shrinkages due to failure to meet targeted error tolerances, since the last call to ResetStatistics or Initialize(). More...
 
int64_t get_num_derivative_evaluations () const
 Returns the number of ODE function evaluations (calls to CalcTimeDerivatives()) since the last call to ResetStatistics() or Initialize(). More...
 
const T & get_actual_initial_step_size_taken () const
 The actual size of the successful first step. More...
 
const T & get_smallest_adapted_step_size_taken () const
 The size of the smallest step taken as the result of a controlled integration step adjustment since the last Initialize() or ResetStatistics() call. More...
 
const T & get_largest_step_size_taken () const
 The size of the largest step taken since the last Initialize() or ResetStatistics() call. More...
 
int64_t get_num_steps_taken () const
 The number of integration steps taken since the last Initialize() or ResetStatistics() call. More...
 
const Eigen::VectorXd & get_generalized_state_weight_vector () const
 Gets the weighting vector (equivalent to a diagonal matrix) applied to weighting both generalized coordinate and velocity state variable errors, as described in the group documentation. More...
 
Eigen::VectorBlock< Eigen::VectorXd > get_mutable_generalized_state_weight_vector ()
 Gets a mutable weighting vector (equivalent to a diagonal matrix) applied to weighting both generalized coordinate and velocity state variable errors, as described in the group documentation. More...
 
const Eigen::VectorXd & get_misc_state_weight_vector () const
 Gets the weighting vector (equivalent to a diagonal matrix) for weighting errors in miscellaneous continuous state variables z. More...
 
Eigen::VectorBlock< Eigen::VectorXd > get_mutable_misc_state_weight_vector ()
 Gets a mutable weighting vector (equivalent to a diagonal matrix) for weighting errors in miscellaneous continuous state variables z. More...
 

Additional Inherited Members

- Protected Member Functions inherited from IntegratorBase< T >
void CalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *dxdt)
 Evaluates the derivative function (and updates call statistics). More...
 
template<typename U >
void CalcTimeDerivatives (const System< U > &system, const Context< U > &context, ContinuousState< U > *dxdt)
 Evaluates the derivative function (and updates call statistics). More...
 
void set_accuracy_in_use (double accuracy)
 Sets the working ("in use") accuracy for this integrator. More...
 
bool StepOnceErrorControlledAtMost (const T &dt_max)
 Default code for advancing the continuous state of the system by a single step of dt_max (or smaller, depending on error control). More...
 
CalcStateChangeNorm (const ContinuousState< T > &dx_state) const
 Computes the infinity norm of a change in continuous state. More...
 
std::pair< bool, T > CalcAdjustedStepSize (const T &err, bool dt_was_artificially_limited, const T &current_step_size) const
 Calculates adjusted integrator step sizes toward keeping state variables within error bounds on the next integration step. More...
 
virtual void DoReset ()
 Derived classes can override this method to perform routines when Reset() is called. More...
 
ContinuousState< T > * get_mutable_error_estimate ()
 Gets an error estimate of the state variables recorded by the last call to StepOnceFixedSize(). More...
 
void set_actual_initial_step_size_taken (const T &dt)
 
void set_smallest_adapted_step_size_taken (const T &dt)
 Sets the size of the smallest-step-taken statistic as the result of a controlled integration step adjustment. More...
 
void set_largest_step_size_taken (const T &dt)
 
void set_ideal_next_step_size (const T &dt)
 

Detailed Description

template<class T>
class drake::systems::ImplicitEulerIntegrator< T >

A first-order, fully implicit integrator with second order error estimation.

Template Parameters
TThe vector element type, which must be a valid Eigen scalar.

This class uses Drake's -inl.h pattern. When seeing linker errors from this class, please refer to http://drake.mit.edu/cxx_inl.html.

Instantiated templates for the following kinds of T's are provided:

  • double
  • AutoDiffXd

This integrator uses the following update rule:

x(t+h) = x(t) + h f(t+h,x(t+h))

where x are the state variables, h is the integration step size, and f() returns the time derivatives of the state variables. Contrast this update rule to that of an explicit first-order integrator:

x(t+h) = x(t) + h f(t, x(t))

Thus implicit first-order integration must solve a nonlinear system of equations to determine both the state at t+h and the time derivatives of that state at that time. Cast as a nonlinear system of equations, we seek the solution to:

x(t+h) - x(t) - h f(t+h,x(t+h)) = 0

given unknowns x(t+h).

This "implicit Euler" method is known to be L-Stable, meaning both that applying it at a fixed integration step to the "test" equation y(t) = eᵏᵗ yields zero (for k < 0 and t → ∞) and that it is also A-Stable. A-Stability, in turn, means that the method can integrate the linear constant coefficient system dx/dt = Ax at any step size without the solution becoming unstable (growing without bound). The practical effect of L-Stability is that the integrator tends to be stable for any given step size on an arbitrary system of ordinary differential equations. See [Lambert, 1991], Ch. 6 for an approachable discussion on stiff differential equations and L- and A-Stability.

The time complexity of this method is often dominated by the time to form the Jacobian matrix consisting of the partial derivatives of the nonlinear system (of n dimensions, where n is the number of state variables) taken with respect to the partial derivatives of the state variables at x(t+h). For typical numerical differentiation, f will be evaluated n times during the Jacobian formation; if we liberally assume that the derivative function evaluation code runs in O(n) time (e.g., as it would for multi-rigid body dynamics without kinematic loops), the asymptotic complexity to form the Jacobian will be O(n²). This Jacobian matrix needs to be formed repeatedly- as often as every time the state variables are updated- during the solution process. Using automatic differentiation replaces the n derivative evaluations with what is hopefully a much less expensive process, though the complexity to form the Jacobian matrix is still O(n²). For large n, the time complexity may be dominated by the O(n³) time required to (repeatedly) solve linear systems problems as part of the nonlinear system solution process.

This implementation uses Newton-Raphson (NR) and relies upon the obvious convergence to a solution for g = 0 where g(x(t+h)) ≡ x(t+h) - x(t) - h f(t+h,x(t+h)) as h becomes sufficiently small. It also uses the implicit trapezoid method- fed the result from implicit Euler for (hopefully) faster convergence- to compute the error estimate. General implementational details were gleaned from [Hairer, 1996].

  • [Hairer, 1996] E. Hairer and G. Wanner. Solving Ordinary Differential Equations II (Stiff and Differential-Algebraic Problems). Springer, 1996.
  • [Lambert, 1991] J. D. Lambert. Numerical Methods for Ordinary Differential Equations. John Wiley & Sons, 1991.

Member Enumeration Documentation

Selecting the wrong such Jacobian determination scheme will slow (possibly critically) the implicit integration process.

Automatic differentiation is recommended if the System supports it for reasons of both higher accuracy and increased speed. Forward differencing (i.e., numerical differentiation) exhibits error in the approximation close to √ε, where ε is machine epsilon, from n forward dynamics calls (where n is the number of state variables). Central differencing yields the most accurate numerically differentiated Jacobian matrix, but expends double the computational effort for approximately three digits greater accuracy: the total error in the central-difference approximation is close to ε^(2/3), from 2n forward dynamics calls. See [Nocedal 2004, pp. 167-169].

  • [Nocedal 2004] J. Nocedal and S. Wright. Numerical Optimization. Springer, 2004.
Enumerator
kForwardDifference 

O(h) Forward differencing.

kCentralDifference 

O(h²) Central differencing.

kAutomatic 

Automatic differentiation.

Constructor & Destructor Documentation

~ImplicitEulerIntegrator ( )
overridedefault
ImplicitEulerIntegrator ( const System< T > &  system,
Context< T > *  context = nullptr 
)
inlineexplicit

Here is the call graph for this function:

Member Function Documentation

int get_error_estimate_order ( ) const
inlineoverridevirtual

This integrator provides second order error estimates.

Implements IntegratorBase< T >.

JacobianComputationScheme get_jacobian_computation_scheme ( ) const
inline
int64_t get_num_derivative_evaluations_for_jacobian ( ) const
inline

Gets the number of ODE function evaluations (calls to CalcTimeDerivatives()) used only for computing the Jacobian matrices since the last call to ResetStatistics().

This count includes those derivative calculations necessary for computing Jacobian matrices during the error estimation process.

int64_t get_num_error_estimator_derivative_evaluations ( ) const
inline

Gets the number of ODE function evaluations (calls to CalcTimeDerivatives()) used only for the error estimation process since the last call to ResetStatistics().

This count includes all such calls including (1) those necessary to compute Jacobian matrices; and (2) calls that exhibit little cost (due to results being cached).

int64_t get_num_error_estimator_derivative_evaluations_for_jacobian ( ) const
inline
int64_t get_num_error_estimator_iteration_matrix_factorizations ( ) const
inline

Gets the number of factorizations of the iteration matrix used only during the error estimation process since the last call to ResetStatistics().

int64_t get_num_error_estimator_jacobian_evaluations ( ) const
inline

Gets the number of Jacobian matrix evaluations used only during the error estimation process since the last call to ResetStatistics().

int64_t get_num_error_estimator_newton_raphson_iterations ( ) const
inline

Gets the number of iterations used in the Newton-Raphson nonlinear systems of equation solving process for the error estimation process since the last call to ResetStatistics().

int64_t get_num_iteration_matrix_factorizations ( ) const
inline

Gets the number of factorizations of the iteration matrix since the last call to ResetStatistics().

This count includes those refactorizations necessary during the error estimation process.

int64_t get_num_jacobian_evaluations ( ) const
inline

Gets the number of Jacobian evaluations (i.e., the number of times that the Jacobian matrix was reformed) since the last call to ResetStatistics().

This count includes those evaluations necessary during the error estimation process.

int64_t get_num_newton_raphson_iterations ( ) const
inline

Gets the number of iterations used in the Newton-Raphson nonlinear systems of equation solving process since the last call to ResetStatistics().

This count includes those Newton-Raphson iterations used during the error estimation process.

bool get_reuse ( ) const
inline

Gets whether the integrator attempts to reuse Jacobian matrices and iteration matrix factorizations.

See also
set_reuse()
ImplicitEulerIntegrator& operator= ( ImplicitEulerIntegrator< T > &&  )
delete
ImplicitEulerIntegrator& operator= ( const ImplicitEulerIntegrator< T > &  )
delete
void set_jacobian_computation_scheme ( JacobianComputationScheme  scheme)
inline

Sets the Jacobian computation scheme.

This function can be safely called at any time (i.e., the integrator need not be re-initialized afterward).

Note
Discards any already-computed Jacobian matrices if the scheme changes.
void set_reuse ( bool  reuse)
inline

Sets whether the integrator attempts to reuse Jacobian matrices and iteration matrix factorizations (default is true).

Forming Jacobian matrices and factorizing iteration matrices are generally the two most expensive operations performed by this integrator. For small systems (those with on the order of ten state variables), the additional accuracy that using fresh Jacobians and factorizations buys- which can permit increased step sizes but should have no effect on solution accuracy- can outweigh the small factorization cost.

See also
get_reuse
bool supports_error_estimation ( ) const
inlineoverridevirtual

The integrator supports error estimation.

Implements IntegratorBase< T >.


The documentation for this class was generated from the following files: