Drake
Drake C++ Documentation
ImplicitIntegrator< T > Class Template Referenceabstract

Detailed Description

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

An abstract class providing methods shared by implicit integrators.

Template Parameters
TThe scalar type, which must be one of the default nonsymbolic scalars.

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

Classes

class  IterationMatrix
 A class for storing the factorization of an iteration matrix and using it to solve linear systems of equations. More...
 

Public Types

enum  JacobianComputationScheme { kForwardDifference, kCentralDifference, kAutomatic }
 
- Public Types inherited from IntegratorBase< T >
enum  StepResult {
  kReachedPublishTime = 1, kReachedZeroCrossing = 2, kReachedUpdateTime = 3, kTimeHasAdvanced = 4,
  kReachedBoundaryTime = 5, kReachedStepLimit = 6
}
 Status returned by IntegrateNoFurtherThanTime(). More...
 

Public Member Functions

virtual ~ImplicitIntegrator ()
 
 ImplicitIntegrator (const System< T > &system, Context< T > *context=nullptr)
 
int max_newton_raphson_iterations () const
 The maximum number of Newton-Raphson iterations to take before the Newton-Raphson process decides that convergence will not be attained. More...
 
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.

Selecting the wrong 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.
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_use_full_newton (bool flag)
 Sets whether the method operates in "full Newton" mode, in which case Jacobian and iteration matrices are freshly computed on every Newton-Raphson iteration. More...
 
bool get_use_full_newton () const
 Gets whether this method is operating in "full Newton" mode. 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_derivative_evaluations_for_jacobian () const
 Gets the number of ODE function evaluations (calls to EvalTimeDerivatives()) used only for computing the Jacobian matrices since the last call to ResetStatistics(). More...
 
int64_t get_num_jacobian_evaluations () const
 Gets the number of Jacobian computations (i.e., the number of times that the Jacobian matrix was reformed) 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_iteration_matrix_factorizations () const
 Gets the number of factorizations of the iteration matrix since the last call to ResetStatistics(). More...
 
int64_t get_num_error_estimator_derivative_evaluations () const
 Gets the number of ODE function evaluations (calls to EvalTimeDerivatives()) used only for the error estimation process 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 computations 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
 
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...
 
StepResult IntegrateNoFurtherThanTime (const T &publish_time, const T &update_time, const T &boundary_time)
 (Internal use only) 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...
 
void IntegrateWithMultipleStepsToTime (const T &t_final)
 Stepping function for integrators operating outside of Simulator that advances the continuous state exactly to t_final. More...
 
bool IntegrateWithSingleFixedStepToTime (const T &t_target)
 Stepping function for integrators operating outside of Simulator that advances the continuous state using a single step to t_target. 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...
 
 IntegratorBase (const IntegratorBase &)=delete
 
IntegratorBaseoperator= (const IntegratorBase &)=delete
 
 IntegratorBase (IntegratorBase &&)=delete
 
IntegratorBaseoperator= (IntegratorBase &&)=delete
 
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...
 
virtual bool supports_error_estimation () const =0
 Derived classes must override this function to indicate whether the integrator supports error estimation. More...
 
virtual int get_error_estimate_order () const =0
 Derived classes must override this function to return the order of the asymptotic term in the integrator's error estimate. More...
 
const ContinuousState< T > * get_error_estimate () const
 Gets the error estimate (used only for integrators that support error estimation). 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...
 
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...
 
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...
 
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...
 
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...
 
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 IntegrateNoFurtherThanTime(). More...
 
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::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...
 
void add_derivative_evaluations (double evals)
 Manually increments the statistic for the number of ODE evaluations. More...
 
void StartDenseIntegration ()
 Starts dense integration, allocating a new dense output for this integrator to use. More...
 
const trajectories::PiecewisePolynomial< T > * get_dense_output () const
 Returns a const pointer to the integrator's current PiecewisePolynomial instance, holding a representation of the continuous state trajectory since the last StartDenseIntegration() call. More...
 
std::unique_ptr< trajectories::PiecewisePolynomial< T > > StopDenseIntegration ()
 Stops dense integration, yielding ownership of the current dense output to the caller. More...
 

Protected Types

enum  ConvergenceStatus { kDiverged, kConverged, kNotConverged }
 

Protected Member Functions

virtual int do_max_newton_raphson_iterations () const
 Derived classes can override this method to change the number of Newton-Raphson iterations (10 by default) to take before the Newton-Raphson process decides that convergence will not be attained. More...
 
bool MaybeFreshenMatrices (const T &t, const VectorX< T > &xt, const T &h, int trial, const std::function< void(const MatrixX< T > &J, const T &h, typename ImplicitIntegrator< T >::IterationMatrix *)> &compute_and_factor_iteration_matrix, typename ImplicitIntegrator< T >::IterationMatrix *iteration_matrix)
 Computes necessary matrices (Jacobian and iteration matrix) for Newton-Raphson (NR) iterations, as necessary. More...
 
void FreshenMatricesIfFullNewton (const T &t, const VectorX< T > &xt, const T &h, const std::function< void(const MatrixX< T > &J, const T &h, typename ImplicitIntegrator< T >::IterationMatrix *)> &compute_and_factor_iteration_matrix, typename ImplicitIntegrator< T >::IterationMatrix *iteration_matrix)
 Computes necessary matrices (Jacobian and iteration matrix) for full Newton-Raphson (NR) iterations, if full Newton-Raphson method is activated (if it's not activated, this method is a no-op). More...
 
bool IsUpdateZero (const VectorX< T > &xc, const VectorX< T > &dxc, double eps=-1.0) const
 Checks whether a proposed update is effectively zero, indicating that the Newton-Raphson process converged. More...
 
ConvergenceStatus CheckNewtonConvergence (int iteration, const VectorX< T > &xtplus, const VectorX< T > &dx, const T &dx_norm, const T &last_dx_norm) const
 Checks a Newton-Raphson iteration process for convergence. More...
 
virtual void DoResetImplicitIntegratorStatistics ()
 Resets any statistics particular to a specific implicit integrator. More...
 
virtual void DoImplicitIntegratorReset ()
 Derived classes can override this method to perform routines when Reset() is called. More...
 
virtual void DoResetCachedJacobianRelatedMatrices ()
 Resets any cached Jacobian or iteration matrices owned by child classes. More...
 
bool IsBadJacobian (const MatrixX< T > &J) const
 Checks to see whether a Jacobian matrix is "bad" (has any NaN or Inf values) and needs to be recomputed. More...
 
virtual int64_t do_get_num_newton_raphson_iterations () const =0
 
virtual int64_t do_get_num_error_estimator_derivative_evaluations () const =0
 
virtual int64_t do_get_num_error_estimator_derivative_evaluations_for_jacobian () const =0
 
virtual int64_t do_get_num_error_estimator_newton_raphson_iterations () const =0
 
virtual int64_t do_get_num_error_estimator_jacobian_evaluations () const =0
 
virtual int64_t do_get_num_error_estimator_iteration_matrix_factorizations () const =0
 
MatrixX< T > & get_mutable_jacobian ()
 
void DoResetStatistics () override
 Resets any statistics particular to a specific integrator. More...
 
void DoReset () final
 Derived classes can override this method to perform routines when Reset() is called. More...
 
const MatrixX< T > & CalcJacobian (const T &t, const VectorX< T > &x)
 
void ComputeForwardDiffJacobian (const System< T > &system, const T &t, const VectorX< T > &xt, Context< T > *context, MatrixX< T > *J)
 
void ComputeCentralDiffJacobian (const System< T > &system, const T &t, const VectorX< T > &xt, Context< T > *context, MatrixX< T > *J)
 
void ComputeAutoDiffJacobian (const System< T > &system, const T &t, const VectorX< T > &xt, const Context< T > &context, MatrixX< T > *J)
 
virtual bool DoImplicitIntegratorStep (const T &h)=0
 Derived classes must implement this method to (1) integrate the continuous portion of this system forward by a single step of size h and (2) set the error estimate (via get_mutable_error_estimate()). More...
 
void increment_num_iter_factorizations ()
 
void increment_jacobian_computation_derivative_evaluations (int count)
 
void increment_jacobian_evaluations ()
 
void set_jacobian_is_fresh (bool flag)
 
template<>
void ComputeAutoDiffJacobian (const System< AutoDiffXd > &, const AutoDiffXd &, const VectorX< AutoDiffXd > &, const Context< AutoDiffXd > &, MatrixX< AutoDiffXd > *)
 
- Protected Member Functions inherited from IntegratorBase< T >
const ContinuousState< T > & EvalTimeDerivatives (const Context< T > &context)
 Evaluates the derivative function and updates call statistics. More...
 
template<typename U >
const ContinuousState< U > & EvalTimeDerivatives (const System< U > &system, const Context< U > &context)
 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 &h_max)
 Default code for advancing the continuous state of the system by a single step of h_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, const T &attempted_step_size, bool *at_minimum_step_size) const
 Calculates adjusted integrator step sizes toward keeping state variables within error bounds on the next integration step. More...
 
virtual void DoInitialize ()
 Derived classes can override this method to perform special initialization. More...
 
trajectories::PiecewisePolynomial< T > * get_mutable_dense_output ()
 Returns a mutable pointer to the internally-maintained PiecewisePolynomial instance, holding a representation of the continuous state trajectory since the last time StartDenseIntegration() was called. More...
 
bool DoDenseStep (const T &h)
 Calls DoStep(h) while recording the resulting step in the dense output. 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 &h)
 
void set_smallest_adapted_step_size_taken (const T &h)
 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 &h)
 
void set_ideal_next_step_size (const T &h)
 

Member Enumeration Documentation

◆ ConvergenceStatus

enum ConvergenceStatus
strongprotected
Enumerator
kDiverged 
kConverged 
kNotConverged 

◆ JacobianComputationScheme

Enumerator
kForwardDifference 

Forward differencing.

kCentralDifference 

Central differencing.

kAutomatic 

Automatic differentiation.

Constructor & Destructor Documentation

◆ ~ImplicitIntegrator()

virtual ~ImplicitIntegrator ( )
virtual

◆ ImplicitIntegrator()

ImplicitIntegrator ( const System< T > &  system,
Context< T > *  context = nullptr 
)
explicit

Member Function Documentation

◆ CalcJacobian()

const MatrixX<T>& CalcJacobian ( const T &  t,
const VectorX< T > &  x 
)
protected

◆ CheckNewtonConvergence()

ConvergenceStatus CheckNewtonConvergence ( int  iteration,
const VectorX< T > &  xtplus,
const VectorX< T > &  dx,
const T &  dx_norm,
const T &  last_dx_norm 
) const
protected

Checks a Newton-Raphson iteration process for convergence.

The logic is based on the description on p. 121 from [Hairer, 1996] E. Hairer and G. Wanner. Solving Ordinary Differential Equations II (Stiff and Differential-Algebraic Problems). Springer, 1996. This function is called after the dx is computed in an iteration, to determine if the Newton process converged, diverged, or needs further iterations.

Parameters
iterationthe iteration index, starting at 0 for the first iteration.
xtplusthe state x at the current iteration.
dxthe state change dx the difference between xtplus at the current and the previous iteration.
dx_normthe weighted norm of dx
last_dx_normthe weighted norm of dx from the previous iteration. This parameter is ignored during the first iteration.
Returns
kConverged for convergence, kDiverged for divergence, otherwise kNotConverged if Newton-Raphson should simply continue.

◆ ComputeAutoDiffJacobian() [1/2]

void ComputeAutoDiffJacobian ( const System< T > &  system,
const T &  t,
const VectorX< T > &  xt,
const Context< T > &  context,
MatrixX< T > *  J 
)
protected

◆ ComputeAutoDiffJacobian() [2/2]

void ComputeAutoDiffJacobian ( const System< AutoDiffXd > &  ,
const AutoDiffXd ,
const VectorX< AutoDiffXd > &  ,
const Context< AutoDiffXd > &  ,
MatrixX< AutoDiffXd > *   
)
protected

◆ ComputeCentralDiffJacobian()

void ComputeCentralDiffJacobian ( const System< T > &  system,
const T &  t,
const VectorX< T > &  xt,
Context< T > *  context,
MatrixX< T > *  J 
)
protected

◆ ComputeForwardDiffJacobian()

void ComputeForwardDiffJacobian ( const System< T > &  system,
const T &  t,
const VectorX< T > &  xt,
Context< T > *  context,
MatrixX< T > *  J 
)
protected

◆ do_get_num_error_estimator_derivative_evaluations()

virtual int64_t do_get_num_error_estimator_derivative_evaluations ( ) const
protectedpure virtual

◆ do_get_num_error_estimator_derivative_evaluations_for_jacobian()

virtual int64_t do_get_num_error_estimator_derivative_evaluations_for_jacobian ( ) const
protectedpure virtual

◆ do_get_num_error_estimator_iteration_matrix_factorizations()

virtual int64_t do_get_num_error_estimator_iteration_matrix_factorizations ( ) const
protectedpure virtual

◆ do_get_num_error_estimator_jacobian_evaluations()

virtual int64_t do_get_num_error_estimator_jacobian_evaluations ( ) const
protectedpure virtual

◆ do_get_num_error_estimator_newton_raphson_iterations()

virtual int64_t do_get_num_error_estimator_newton_raphson_iterations ( ) const
protectedpure virtual

◆ do_get_num_newton_raphson_iterations()

virtual int64_t do_get_num_newton_raphson_iterations ( ) const
protectedpure virtual

◆ do_max_newton_raphson_iterations()

virtual int do_max_newton_raphson_iterations ( ) const
protectedvirtual

Derived classes can override this method to change the number of Newton-Raphson iterations (10 by default) to take before the Newton-Raphson process decides that convergence will not be attained.

◆ DoImplicitIntegratorReset()

virtual void DoImplicitIntegratorReset ( )
protectedvirtual

Derived classes can override this method to perform routines when Reset() is called.

This default method does nothing.

◆ DoImplicitIntegratorStep()

virtual bool DoImplicitIntegratorStep ( const T &  h)
protectedpure virtual

Derived classes must implement this method to (1) integrate the continuous portion of this system forward by a single step of size h and (2) set the error estimate (via get_mutable_error_estimate()).

This method is called during the integration process (via StepOnceErrorControlledAtMost(), IntegrateNoFurtherThanTime(), and IntegrateWithSingleFixedStepToTime()).

Parameters
hThe integration step to take.
Returns
true if successful, false if the integrator was unable to take a single step of size h (due to, e.g., an integrator convergence failure).
Postcondition
If the time on entry is denoted t, the time and state will be advanced to t+h if the method returns true; otherwise, the time and state should be reset to those at t.
Warning
It is expected that DoStep() will return true for some, albeit possibly very small, positive value of h. The derived integrator's stepping algorithm can make this guarantee, for example, by switching to an algorithm not subject to convergence failures (e.g., explicit Euler) for very small step sizes.

◆ DoReset()

void DoReset ( )
finalprotectedvirtual

Derived classes can override this method to perform routines when Reset() is called.

This default method does nothing.

Reimplemented from IntegratorBase< T >.

◆ DoResetCachedJacobianRelatedMatrices()

virtual void DoResetCachedJacobianRelatedMatrices ( )
protectedvirtual

Resets any cached Jacobian or iteration matrices owned by child classes.

This is called when the user changes the Jacobian computation scheme; the child class should use this to reset its cached matrices.

◆ DoResetImplicitIntegratorStatistics()

virtual void DoResetImplicitIntegratorStatistics ( )
protectedvirtual

Resets any statistics particular to a specific implicit integrator.

The default implementation of this function does nothing. If your integrator collects its own statistics, you should re-implement this method and reset them there.

◆ DoResetStatistics()

void DoResetStatistics ( )
overrideprotectedvirtual

Resets any statistics particular to a specific integrator.

The default implementation of this function does nothing. If your integrator collects its own statistics, you should re-implement this method and reset them there.

Reimplemented from IntegratorBase< T >.

◆ FreshenMatricesIfFullNewton()

void FreshenMatricesIfFullNewton ( const T &  t,
const VectorX< T > &  xt,
const T &  h,
const std::function< void(const MatrixX< T > &J, const T &h, typename ImplicitIntegrator< T >::IterationMatrix *)> &  compute_and_factor_iteration_matrix,
typename ImplicitIntegrator< T >::IterationMatrix iteration_matrix 
)
protected

Computes necessary matrices (Jacobian and iteration matrix) for full Newton-Raphson (NR) iterations, if full Newton-Raphson method is activated (if it's not activated, this method is a no-op).

Parameters
tthe time at which to compute the Jacobian.
xtthe continuous state at which the Jacobian is computed.
hthe integration step size (for computing iteration matrices).
compute_and_factor_iteration_matrixa function pointer for computing and factoring the iteration matrix.
[out]iteration_matrixthe updated and factored iteration matrix on return.
Postcondition
the state in the internal context will be set to (t, xt) and this will store the updated Jacobian matrix, on return.

◆ get_jacobian_computation_scheme()

JacobianComputationScheme get_jacobian_computation_scheme ( ) const

◆ get_mutable_jacobian()

MatrixX<T>& get_mutable_jacobian ( )
protected

◆ get_num_derivative_evaluations_for_jacobian()

int64_t get_num_derivative_evaluations_for_jacobian ( ) const

Gets the number of ODE function evaluations (calls to EvalTimeDerivatives()) 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 error estimation processes.

◆ get_num_error_estimator_derivative_evaluations()

int64_t get_num_error_estimator_derivative_evaluations ( ) const

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

This count includes those needed to compute Jacobian matrices.

◆ get_num_error_estimator_derivative_evaluations_for_jacobian()

int64_t get_num_error_estimator_derivative_evaluations_for_jacobian ( ) const

◆ get_num_error_estimator_iteration_matrix_factorizations()

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().

◆ get_num_error_estimator_jacobian_evaluations()

int64_t get_num_error_estimator_jacobian_evaluations ( ) const

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

◆ get_num_error_estimator_newton_raphson_iterations()

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().

◆ get_num_iteration_matrix_factorizations()

int64_t get_num_iteration_matrix_factorizations ( ) const

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

This count includes those refactorizations necessary during error estimation processes.

◆ get_num_jacobian_evaluations()

int64_t get_num_jacobian_evaluations ( ) const

Gets the number of Jacobian computations (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 error estimation processes.

◆ get_num_newton_raphson_iterations()

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().

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

◆ get_reuse()

bool get_reuse ( ) const

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

See also
set_reuse()
Note
This method always returns false when full-Newton mode is on.

◆ get_use_full_newton()

bool get_use_full_newton ( ) const

Gets whether this method is operating in "full Newton" mode.

See also
set_use_full_newton()

◆ increment_jacobian_computation_derivative_evaluations()

void increment_jacobian_computation_derivative_evaluations ( int  count)
protected

◆ increment_jacobian_evaluations()

void increment_jacobian_evaluations ( )
protected

◆ increment_num_iter_factorizations()

void increment_num_iter_factorizations ( )
protected

◆ IsBadJacobian()

bool IsBadJacobian ( const MatrixX< T > &  J) const
protected

Checks to see whether a Jacobian matrix is "bad" (has any NaN or Inf values) and needs to be recomputed.

A divergent Newton-Raphson iteration can cause the state to overflow, which is how the Jacobian can become "bad". This is an O(n²) operation, where n is the state dimension.

◆ IsUpdateZero()

bool IsUpdateZero ( const VectorX< T > &  xc,
const VectorX< T > &  dxc,
double  eps = -1.0 
) const
protected

Checks whether a proposed update is effectively zero, indicating that the Newton-Raphson process converged.

Parameters
xcthe continuous state.
dxcthe update to the continuous state.
epsthe tolerance that will be used to determine whether the change in any dimension of the state is nonzero. eps will be treated as an absolute tolerance when the magnitude of a particular dimension of the state is no greater than unity and as a relative tolerance otherwise. For non-positive eps (default), an appropriate tolerance will be computed.
Returns
true if the update is effectively zero.

◆ max_newton_raphson_iterations()

int max_newton_raphson_iterations ( ) const

The maximum number of Newton-Raphson iterations to take before the Newton-Raphson process decides that convergence will not be attained.

This number affects the speed with which a solution is found. If the number is too small, Jacobian/iteration matrix reformations and refactorizations will be performed unnecessarily. If the number is too large, the Newton-Raphson process will waste time evaluating derivatives when convergence is infeasible. [Hairer, 1996] states, "It is our experience that the code becomes more efficient when we allow a relatively high number of iterations (e.g., [7 or 10])", p. 121. Note that the focus of that quote is a 5th order integrator that uses a quasi-Newton approach.

◆ MaybeFreshenMatrices()

bool MaybeFreshenMatrices ( const T &  t,
const VectorX< T > &  xt,
const T &  h,
int  trial,
const std::function< void(const MatrixX< T > &J, const T &h, typename ImplicitIntegrator< T >::IterationMatrix *)> &  compute_and_factor_iteration_matrix,
typename ImplicitIntegrator< T >::IterationMatrix iteration_matrix 
)
protected

Computes necessary matrices (Jacobian and iteration matrix) for Newton-Raphson (NR) iterations, as necessary.

This method has been designed for use in DoImplicitIntegratorStep() processes that follow this model:

  1. DoImplicitIntegratorStep(h) is called;
  2. One or more NR iterations is performed until either (a) convergence is identified, (b) the iteration is found to diverge, or (c) too many iterations were taken. In the case of (a), DoImplicitIntegratorStep(h) will return success. Otherwise, the Newton-Raphson process is attempted again with (i) a recomputed and refactored iteration matrix and (ii) a recomputed Jacobian and a recomputed an refactored iteration matrix, in that order. The process stage of that NR algorithm is indicated by the trial parameter below. In this model, DoImplicitIntegratorStep() returns failure if the NR iterations reach a fourth trial.

Note that the sophisticated logic above only applies when the Jacobian reuse is activated (default, see get_reuse()).

Parameters
tthe time at which to compute the Jacobian.
xtthe continuous state at which the Jacobian is computed.
hthe integration step size (for computing iteration matrices).
trialwhich trial (1-4) the Newton-Raphson process is in when calling this method.
compute_and_factor_iteration_matrixa function pointer for computing and factoring the iteration matrix.
[out]iteration_matrixthe updated and factored iteration matrix on return.
Returns
false if the calling stepping method should indicate failure; true otherwise.
Precondition
1 <= trial <= 4.
Postcondition
the state in the internal context may or may not be altered on return; if altered, it will be set to (t, xt).

◆ set_jacobian_computation_scheme()

void set_jacobian_computation_scheme ( JacobianComputationScheme  scheme)

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.

◆ set_jacobian_is_fresh()

void set_jacobian_is_fresh ( bool  flag)
protected

◆ set_reuse()

void set_reuse ( bool  reuse)

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.

Note
The reuse setting will have no effect when get_use_full_newton() == true.
See also
get_reuse()
set_use_full_newton()

◆ set_use_full_newton()

void set_use_full_newton ( bool  flag)

Sets whether the method operates in "full Newton" mode, in which case Jacobian and iteration matrices are freshly computed on every Newton-Raphson iteration.

When set to true, this mode overrides the reuse mode.

See also
set_reuse()

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