Drake
integrator_base.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <algorithm>
4 #include <limits>
5 #include <memory>
6 #include <utility>
7 
17 
18 namespace drake {
19 namespace systems {
20 
21 /*
22 TODO(edrumwri): comments below in preparation of upcoming functionality
23  Note: we ensure algorithmically that no report time, scheduled time, or
24 final time t can occur *within* an event window, that is, we will never have
25  t_low < t < t_high for any interesting t. Further, t_report, t_scheduled and
26  t_final can coincide with t_high but only t_report can be at t_low. The
27  interior of t_low:t_high is a "no man's land" where we don't understand the
28 solution, so must be avoided.
29 */
30 
31 /**
32  * An abstract class for an integrator for ODEs and DAEs as represented by a
33  * Drake System. Integrators solve initial value problems of the form:<pre>
34  * ẋ(t) = f(t, x(t)) with f : ℝ × ℝⁿ → ℝⁿ
35  * </pre>
36  * (i.e., `f()` is an ordinary differential equation) given initial conditions
37  * (t₀, x₀). Thus, integrators advance the continuous state of a dynamical
38  * system forward in time.
39  *
40  * Apart from solving initial value problems, for which the integrator is a
41  * key component of a simulator, integrators can also be used to solve
42  * boundary value problems (via numerical methods like the Multiple Shooting
43  * Method) and trajectory optimization problems (via numerical methods like
44  * direct transcription). This class and its derivatives were developed
45  * primarily toward the former application (through IntegrateAtMost() and
46  * the Simulator class). However, the IntegratorBase architecture was developed
47  * to support these ancillary applications as well using the
48  * IntegrateWithMultipleSteps() and IntegrateWithSingleFixedStep() methods;
49  * the latter permits the caller to advance time using fixed steps in
50  * applications where variable stepping would be deleterious (e.g., direct
51  * transcription).
52  *
53  * For applications that require a more dense sampling of the system
54  * continuous state than what would be available through either fixed or
55  * error-controlled step integration (for a given accuracy), dense output
56  * support is available (through StartDenseIntegration() and
57  * StopDenseIntegration() methods). The accuracy and performance of these
58  * outputs may vary with each integration scheme implementation. Unless
59  * specified otherwise, an HermitianDenseOutput is provided by default.
60  *
61  * A natural question for a user to ask of an integrator is: Which scheme
62  * (method) should be applied to a particular problem? The answer is whichever
63  * one most quickly computes the solution to the desired accuracy! Selecting
64  * an integration scheme for a particular problem is presently an artform. As
65  * examples of some selection criteria: multistep methods (none of which are
66  * currently implemented in Drake) generally work poorly when events (that
67  * require state reinitializations) are common, symplectic methods generally
68  * work well at maintaining stability for large integration steps, and stiff
69  * integrators are often best for computationally stiff systems. If ignorant
70  * as to the characteristics of a particular problem, it is often best to start
71  * with an explicit, Runge-Kutta type method. Statistics collected by the
72  * integrator can help diagnose performance issues and possibly point to the
73  * use of a different integration scheme.
74  *
75  * Some systems are known to exhibit "computational stiffness", by which it is
76  * meant that (excessively) small integration steps are necessary for purposes
77  * of stability: in other words, steps must be taken smaller than that
78  * required to achieve a desired accuracy *over a particular interval*.
79  * Thus, the nature of computationally stiff problems is that the solution to
80  * the ODE is *smooth* in the interval of stiffness (in contrast, some problems
81  * possess such high frequency dynamics that very small steps are simply
82  * necessary to capture the solution accurately). Implicit integrators are the
83  * go-to approach for solving computationally stiff problems, but careful
84  * consideration is warranted. Implicit integrators typically require much more
85  * computation than non-implicit (explicit) integrators, stiffness might be an
86  * issue on only a very small time interval, and some problems might be only
87  * "moderately stiff". Put another way, applying an implicit integrator to a
88  * potentially stiff problem might not yield faster computation. The first
89  * chapter of [Hairer, 1996] illustrates the issues broached in this paragraph
90  * using various examples.
91  *
92  * Established methods for integrating ordinary differential equations
93  * invariably make provisions for estimating the "local error" (i.e., the
94  * error over a small time interval) of a solution. Although the relationship
95  * between local error and global error (i.e., the accumulated error over
96  * multiple time steps) can be tenuous, such error estimates can allow
97  * integrators to work adaptively, subdividing time intervals as necessary
98  * (if, e.g., the system is particularly dynamic or stationary in an interval).
99  * Even for applications that do not recommend such adaptive integration- like
100  * direct transcription methods for trajectory optimization- error estimation
101  * allows the user to assess the accuracy of the solution.
102  *
103  * IntegratorBase provides numerous settings and flags that can leverage
104  * problem-specific information to speed integration and/or improve integration
105  * accuracy. As an example, set_maximum_step_size() allows the user to prevent
106  * overly large integration steps (that integration error control alone might
107  * be insufficient to detect). As noted previously, IntegratorBase also collects
108  * a plethora of statistics that can be used to diagnose poor integration
109  * performance. For example, a large number of shrinkages due to error control
110  * could indicate that a system is computationally stiff.
111  *
112  * - [Hairer, 1996] E. Hairer and G. Wanner. Solving Ordinary Differential
113  * Equations II (Stiff and Differential-Algebraic Problems).
114  * Springer, 1996.
115 
116  * @tparam T The vector element type, which must be a valid Eigen scalar.
117  */
118 template <class T>
120  public:
122 
123  /**
124  * Status returned by StepOnceAtMost().
125  * When a step is successful, it will return an indication of what caused it
126  * to stop where it did. When unsuccessful it will throw an exception so you
127  * won't see any return value. When return of control is due ONLY to reaching
128  * a publish time, (status is kReachedPublishTime) the context may return an
129  * interpolated value at an earlier time.
130  *
131  * Note: the simulation step must always end at an update time but can end
132  * after a publish time.
133  */
134  // TODO(edrumwri): incorporate kReachedZeroCrossing into the simulator.
135  enum StepResult {
136  /**
137  * Indicates a publish time has been reached but not an update time.
138  */
140  /**
141  * Localized an event; this is the *before* state (interpolated).
142  */
144  /**
145  * Indicates that integration terminated at an update time.
146  */
148  /**
149  * User requested control whenever an internal step is successful.
150  */
152  /**
153  * Reached the desired integration time without reaching an update time.
154  */
156  /** Took maximum number of steps without finishing integrating over the
157  * interval. */
159  };
160 
161  /**
162  * Maintains references to the system being integrated and the context used
163  * to specify the initial conditions for that system (if any).
164  * @param system A reference to the system to be integrated; the integrator
165  * will maintain a reference to the system in perpetuity, so
166  * the integrator must not outlive the system.
167  * @param context A pointer to a writeable context (nullptr is ok, but a
168  * non-null pointer must be set before Initialize() is
169  * called). The integrator will advance the system state using
170  * the pointer to this context. The pointer to the context will
171  * be maintained internally. The integrator must not outlive
172  * the context.
173  */
174  explicit IntegratorBase(const System<T>& system,
175  Context<T>* context = nullptr)
176  : system_(system), context_(context),
177  derivatives_(system.AllocateTimeDerivatives()) {
178  initialization_done_ = false;
179  }
180 
181  /** Destructor. */
182  virtual ~IntegratorBase() = default;
183 
184  /**
185  * Indicates whether an integrator supports error estimation.
186  * Without error estimation, target accuracy will be unused.
187  */
188  virtual bool supports_error_estimation() const = 0;
189 
190  /**
191  * Sets an integrator with error control to fixed step mode. If the integrator
192  * runs in fixed step mode, it will always take the maximum step size
193  * directed (which may be that determined by get_maximum_step_size(), or may
194  * be smaller, as directed by, e.g., Simulator for event handling purposes).
195  * @throws std::logic_error if integrator does not support error
196  * estimation and @p flag is set to `false`.
197  */
198  void set_fixed_step_mode(bool flag) {
199  if (!flag && !supports_error_estimation())
200  throw std::logic_error("Integrator does not support accuracy estimation");
201  fixed_step_mode_ = flag;
202  }
203 
204  /**
205  * Gets whether an integrator is running in fixed step mode. If the integrator
206  * does not support error estimation, this function will always return `true`.
207  * If the integrator runs in fixed step mode, it will always take the maximum
208  * step size directed (which may be that determined by get_maximum_step_size()
209  * or may be smaller, as directed by, e.g., Simulator for event handling
210  * purposes).
211  * @sa set_fixed_step_mode()
212  */
213  bool get_fixed_step_mode() const {
214  return (!supports_error_estimation() || fixed_step_mode_);
215  }
216 
217  /** Request that the integrator attempt to achieve a particular accuracy for
218  * the continuous portions of the simulation. Otherwise a default accuracy is
219  * chosen for you. This may be ignored for fixed-step integration since
220  * accuracy control requires variable step sizes. You should call
221  * supports_error_estimation() to ensure that the
222  * integrator supports this capability before calling this function; if
223  * the integrator does not support it, this method will throw an exception.
224  *
225  * Integrators vary in the range of accuracy (loosest to tightest) that they
226  * can support. If you request accuracy outside the supported range for the
227  * chosen integrator it will be quietly adjusted to be in range. You can find
228  * out the accuracy setting actually being used using `get_accuracy_in_use()`.
229  *
230  * The precise meaning of *accuracy* is a complicated discussion, but
231  * translates roughly to the number of significant digits you want in the
232  * results. By convention it is supplied as `10^-digits`, meaning that an
233  * accuracy of 1e-3 provides about three significant digits. For more
234  * information, see [Sherman 2011].
235  * - M. Sherman, et al. Procedia IUTAM 2:241-261 (2011), Section 3.3.
236  * http://dx.doi.org/10.1016/j.piutam.2011.04.023
237  * @throws std::logic_error if integrator does not support error
238  * estimation.
239  */
240  // TODO(edrumwri): complain if integrator with error estimation wants to drop
241  // below the minimum step size
242  void set_target_accuracy(double accuracy) {
244  throw std::logic_error(
245  "Integrator does not support accuracy estimation "
246  "and user has requested error control");
247  target_accuracy_ = accuracy;
248  accuracy_in_use_ = accuracy;
249  }
250 
251  /**
252  * Gets the target accuracy.
253  * @sa get_accuracy_in_use()
254  */
255  double get_target_accuracy() const { return target_accuracy_; }
256 
257  /**
258  * Gets the accuracy in use by the integrator. This number may differ from
259  * the target accuracy if, for example, the user has requested an accuracy
260  * not attainable or not recommended for the particular integrator.
261  */
262  double get_accuracy_in_use() const { return accuracy_in_use_; }
263 
264  /**
265  * Sets the maximum step size that may be taken by this integrator. The
266  * integrator may stretch the maximum step size by as much as 1% to reach a
267  * discrete event. For fixed step integrators, all steps will be taken at the
268  * maximum step size *unless* an event would be missed.
269  */
270  // TODO(edrumwri): Update this comment when stretch size is configurable.
271  void set_maximum_step_size(const T& max_step_size) {
272  DRAKE_ASSERT(max_step_size >= 0.0);
273  max_step_size_ = max_step_size;
274  }
275 
276  /**
277  * Gets the maximum step size that may be taken by this integrator. This is
278  * a soft maximum: the integrator may stretch it by as much as 1% to hit a
279  * discrete event.
280  * @sa set_requested_minimum_step_size()
281  */
282  // TODO(edrumwri): Update this comment when stretch size is configurable.
283  const T& get_maximum_step_size() const { return max_step_size_; }
284 
285  /**
286  * @anchor Minstep
287  * @name Methods for minimum integration step size selection and behavior
288  *
289  * Variable step integrators reduce their step sizes as needed to achieve
290  * requirements such as specified accuracy or step convergence. However, it is
291  * not possible to take an arbitrarily small step. Normally integrators choose
292  * an appropriate minimum step and throw an exception if the requirements
293  * can't be achieved without going below that. Methods in this section allow
294  * you to influence two aspects of this procedure:
295  * - you can increase the minimum step size, and
296  * - you can control whether an exception is thrown if a smaller step would
297  * have been needed to achieve the aforementioned integrator requirements.
298  *
299  * By default, integrators allow a very small minimum step which can
300  * result in long run times. Setting a larger minimum can be helpful as a
301  * diagnostic to figure out what aspect of your simulation is requiring small
302  * steps. You can set the minimum to what should be a "reasonable" minimum
303  * based on what you know about the physical system. You will then get an
304  * std::runtime_error exception thrown at any point in time where your model
305  * behaves unexpectedly (due to, e.g., a discontinuity in the derivative
306  * evaluation function).
307  *
308  * If you disable the exception (via
309  * `set_throw_on_minimum_step_size_violation(false)`), the integrator will
310  * simply proceed with a step of the minimum size: accuracy is guaranteed
311  * only when the minimum step size is not violated. Beware that there can be
312  * no guarantee about the magnitude of any errors introduced by violating the
313  * accuracy "requirements" in this manner, so disabling the exception should
314  * be done warily.
315  *
316  * #### Details
317  * Because time is maintained to finite precision, there is an absolute
318  * minimum step size `h_floor` required to avoid roundoff error. The
319  * integrator will never take a step smaller than `h_floor`. We calculate
320  * `h_floor=max(ε,ε⋅t)`, where t is the current time and ε is a small multiple
321  * of machine precision, typically a number like 1e-14. Note that `h_floor`
322  * necessarily grows with time; if that is a concern you should limit how
323  * long your simulations are allowed to run without resetting time.
324  *
325  * You may request a larger minimum step size `h_min`. Then at every time t,
326  * the integrator determines a "working" minimum `h_work=max(h_min,h_floor)`.
327  * If the step size selection algorithm determines that a step smaller than
328  * `h_work` is needed to meet accuracy or other needs, then a
329  * std::runtime_error exception will be thrown and the simulation halted. On
330  * the other hand, if you have suppressed the exception (again, via
331  * `set_throw_on_minimum_step_size_violation(false)`), the integration
332  * will continue, taking a step of size `h_work`.
333  *
334  * Under some circumstances the integrator may legitimately take a step of
335  * size `h` smaller than your specified `h_min`, although never smaller than
336  * `h_floor`. For example, occasionally the integrator may reach an event or
337  * time limit that occurs a very short time after the end of a previous step,
338  * necessitating that a tiny "sliver" of a step be taken to complete the
339  * interval. That does not indicate an error, and required accuracy and
340  * convergence goals are achieved. Larger steps can resume immediately
341  * afterwards. Another circumstance is when one of the integrator's stepping
342  * methods is called directly requesting a very small step, for example
343  * `IntegrateWithMultipleSteps(h)`. No exception will be thrown in either of
344  * these cases.
345  */
346 
347  //@{
348  /**
349  * Sets the requested minimum step size `h_min` that may be taken by this
350  * integrator. No step smaller than this will be taken except under
351  * circumstances as described @link Minstep above. @endlink This setting will
352  * be ignored if it is smaller than the absolute minimum `h_floor` also
353  * described above. Default value is zero.
354  * @param min_step_size a non-negative value. Setting this value to zero
355  * will cause the integrator to use a reasonable value
356  * instead (see get_working_minimum_step_size()).
357  * @sa get_requested_minimum_step_size()
358  * @sa get_working_minimum_step_size()
359  */
360  void set_requested_minimum_step_size(const T& min_step_size) {
361  DRAKE_ASSERT(min_step_size >= 0.0);
362  req_min_step_size_ = min_step_size;
363  }
364 
365  /**
366  * Gets the requested minimum step size `h_min` for this integrator.
367  * @sa set_requested_minimum_step_size()
368  * @sa get_working_minimum_step_size(T)
369  */
371  return req_min_step_size_; }
372 
373  /**
374  * Sets whether the integrator should throw a std::runtime_error exception
375  * when the integrator's step size selection algorithm determines that it
376  * must take a step smaller than the minimum step size (for, e.g., purposes
377  * of error control). Default is `true`. If `false`, the integrator will
378  * advance time and state using the minimum specified step size in such
379  * situations. See @link Minstep this section @endlink for more detail.
380  */
382  min_step_exceeded_throws_ = throws;
383  }
384 
385  /**
386  * Reports the current setting of the throw_on_minimum_step_size_violation
387  * flag.
388  * @sa set_throw_on_minimum_step_size_violation().
389  */
391  return min_step_exceeded_throws_;
392  }
393 
394  /**
395  * Gets the current value of the working minimum step size `h_work(t)` for
396  * this integrator, which may vary with the current time t as stored in the
397  * integrator's context.
398  * See @link Minstep this section @endlink for more detail.
399  */
401  using std::max;
402  // Tolerance is just a number close to machine epsilon.
403  const double tol = 1e-14;
404  const T smart_minimum = max(tol, get_context().get_time()*tol);
405  return max(smart_minimum, req_min_step_size_);
406  }
407  //@}
408 
409  /**
410  * Resets the integrator to initial values, i.e., default construction
411  * values.
412  */
413  void Reset() {
414  // Kill the error estimate and weighting matrices.
415  err_est_.reset();
416  qbar_weight_.setZero(0);
417  z_weight_.setZero(0);
418  pinvN_dq_change_.reset();
419  unweighted_substate_change_.setZero(0);
420  weighted_q_change_.reset();
421 
422  // Drops dense output, if any.
423  dense_output_.reset();
424 
425  // Integrator no longer operates in fixed step mode.
426  fixed_step_mode_ = false;
427 
428  // Statistics no longer valid.
429  ResetStatistics();
430 
431  // Wipe out settings.
432  req_min_step_size_ = 0;
433  max_step_size_ = nan();
434  accuracy_in_use_ = nan();
435 
436  // Indicate values used for error controlled integration no longer valid.
437  prev_step_size_ = nan();
438  ideal_next_step_size_ = nan();
439 
440  // Call the derived integrator reset routine.
441  DoReset();
442 
443  // Indicate that initialization is necessary.
444  initialization_done_ = false;
445  }
446 
447  /**
448  * An integrator must be initialized before being used. The pointer to the
449  * context must be set before Initialize() is called (or an std::logic_error
450  * will be thrown). If Initialize() is not called, an exception will be
451  * thrown when attempting to call StepOnceAtMost(). To reinitialize the
452  * integrator, Reset() should be called followed by Initialize().
453  * @throws std::logic_error If the context has not been set or a user-set
454  * parameter has been set illogically (i.e., one of the
455  * weighting matrix coefficients is set to a negative value- this
456  * check is only performed for integrators that support error
457  * estimation; the maximum step size is smaller than the minimum
458  * step size; the requested initial step size is outside of the
459  * interval [minimum step size, maximum step size]).
460  * @sa Reset()
461  */
462  void Initialize() {
463  if (!context_) throw std::logic_error("Context has not been set.");
464 
465  // Verify that user settings are reasonable.
466  if (max_step_size_ < req_min_step_size_) {
467  throw std::logic_error("Integrator maximum step size is less than the "
468  "minimum step size");
469  }
470  if (req_initial_step_size_ > max_step_size_) {
471  throw std::logic_error("Requested integrator initial step size is larger "
472  "than the maximum step size.");
473  }
474  if (req_initial_step_size_ < req_min_step_size_) {
475  throw std::logic_error("Requested integrator initial step size is smaller"
476  " than the minimum step size.");
477  }
478 
479  // TODO(edrumwri): Compute qbar_weight_, z_weight_ automatically.
480  // Set error weighting vectors if not already done.
482  // Allocate space for the error estimate.
483  err_est_ = system_.AllocateTimeDerivatives();
484 
485  const auto& xc = context_->get_state().get_continuous_state();
486  const int gv_size = xc.get_generalized_velocity().size();
487  const int misc_size = xc.get_misc_continuous_state().size();
488  if (qbar_weight_.size() != gv_size) qbar_weight_.setOnes(gv_size);
489  if (z_weight_.size() != misc_size) z_weight_.setOnes(misc_size);
490 
491  // Verify that minimum values of the weighting matrices are non-negative.
492  if ((qbar_weight_.size() && qbar_weight_.minCoeff() < 0) ||
493  (z_weight_.size() && z_weight_.minCoeff() < 0))
494  throw std::logic_error("Scaling coefficient is less than zero.");
495  }
496 
497  // Statistics no longer valid.
498  ResetStatistics();
499 
500  // Call the derived integrator initialization routine (if any)
501  DoInitialize();
502 
503  initialization_done_ = true;
504  }
505 
506  /**
507  * Request that the first attempted integration step have a particular size.
508  * If no request is made, the integrator will estimate a suitable size
509  * for the initial step attempt. *If the integrator does not support error
510  * control*, this method will throw a std::logic_error (call
511  * supports_error_estimation() to verify before calling this method). For
512  * variable-step integration, the initial target will be treated as a maximum
513  * step size subject to accuracy requirements and event occurrences. You can
514  * find out what size *actually* worked with
515  * `get_actual_initial_step_size_taken()`.
516  * @throws std::logic_error If the integrator does not support error
517  * estimation.
518  */
519  void request_initial_step_size_target(const T& step_size) {
520  using std::isnan;
522  throw std::logic_error(
523  "Integrator does not support error estimation and "
524  "user has initial step size target");
525  req_initial_step_size_ = step_size;
526  }
527 
528  /**
529  * Gets the target size of the first integration step. You can find out what
530  * step size was *actually* used for the first integration step with
531  * `get_actual_initial_step_size_taken()`.
532  * @see request_initial_step_size_target()
533  */
534  const T& get_initial_step_size_target() const {
535  return req_initial_step_size_;
536  }
537 
538  /**
539  * Integrates the system forward in time by a single step with step size
540  * subject to integration error tolerances (assuming that the integrator
541  * supports error estimation). The integrator must already have
542  * been initialized or an exception will be thrown. The context will be
543  * integrated forward by an amount that will never exceed the minimum of
544  * `publish_dt`, `update_dt`, and `1.01 * get_maximum_step_size()`.
545  *
546  * @param publish_dt The step size, >= 0.0 (exception will be thrown
547  * if this is not the case) at which the next publish will occur.
548  * @param update_dt The step size, >= 0.0 (exception will be thrown
549  * if this is not the case) at which the next update will occur.
550  * @param boundary_dt The step size, >= 0.0 (exception will be thrown
551  * if this is not the case) marking the end of the user-designated
552  * simulated interval.
553  * @throws std::logic_error If the integrator has not been initialized or one
554  * of publish_dt, update_dt, or boundary_dt is
555  * negative.
556  * @return The reason for the integration step ending.
557  * @warning Users should generally not call this function directly; within
558  * simulation circumstances, users will typically call
559  * `Simulator::StepTo()`. In other circumstances, users will
560  * typically call `IntegratorBase::IntegrateWithMultipleSteps()`.
561  *
562  * This method at a glance:
563  * - For integrating ODEs/DAEs via Simulator
564  * - Supports fixed step and variable step integration schemes
565  * - Takes only a single step forward.
566  */
567  // TODO(edrumwri): Make the stretch size configurable.
568  StepResult IntegrateAtMost(const T& publish_dt, const T& update_dt,
569  const T& boundary_dt);
570 
571  /// Gets the stretch factor (> 1), which is multiplied by the maximum
572  /// (typically user-designated) integration step size to obtain the amount
573  /// that the integrator is able to stretch the maximum time step toward
574  /// hitting an upcoming publish or update event in IntegrateAtMost().
575  /// @sa IntegrateAtMost()
576  double get_stretch_factor() const { return 1.01; }
577 
578  /// Stepping function for integrators operating outside of Simulator that
579  /// advances the continuous state exactly by @p dt. This method is designed
580  /// for integrator users that do not wish to consider publishing or
581  /// discontinuous, mid-interval updates. This method will step the integrator
582  /// multiple times, as necessary, to attain requested error tolerances and
583  /// to ensure the integrator converges.
584  /// @warning Users should simulate systems using `Simulator::StepTo()` in
585  /// place of this function (which was created for off-simulation
586  /// purposes), generally.
587  /// @param dt The non-negative integration step to take.
588  /// @throws std::logic_error If the integrator has not been initialized or
589  /// dt is negative.
590  /// @sa IntegrateAtMost(), which is designed to be operated by Simulator and
591  /// accounts for publishing and state reinitialization.
592  /// @sa IntegrateWithSingleStep(), which is also designed to be operated
593  /// *outside of* Simulator, but throws an exception if the integrator
594  /// cannot advance time by @p dt in a single step.
595  ///
596  /// This method at a glance:
597  /// - For integrating ODEs/DAEs not using Simulator
598  /// - Supports fixed step and variable step integration schemes
599  /// - Takes as many steps as necessary until time has advanced by @p dt
600  void IntegrateWithMultipleSteps(const T& dt) {
601  using std::max;
602  using std::min;
603 
604  const Context<T>& context = get_context();
605  const T inf = std::numeric_limits<double>::infinity();
606  T t_remaining = dt;
607 
608  // Note: A concern below is that the while loop while run forever because
609  // t_remaining could be small, but not quite zero, if dt is relatively
610  // small compared to the context time. In such a case, t_final will be
611  // equal to context.get_time() in the expression immediately below,
612  // context.get_time() will not change during the call to IntegrateAtMost(),
613  // and t_remaining will be equal to zero (meaning that the loop will
614  // indeed terminate, as desired).
615  const T t_final = context.get_time() + t_remaining;
616  do {
617  IntegrateAtMost(inf, inf, min(t_remaining, get_maximum_step_size()));
618  t_remaining = t_final - context.get_time();
619  } while (t_remaining > 0);
620  }
621 
622  /// Stepping function for integrators operating outside of Simulator that
623  /// advances the continuous state exactly by @p dt *and using a single fixed
624  /// step*. This method is designed for integrator users that do not wish to
625  /// consider publishing or discontinuous, mid-interval updates. One such
626  /// example application is that of direct transcription for trajectory
627  /// optimization, for which the integration process should be _consistent_: it
628  /// should execute the same sequence of arithmetic operations for all values
629  /// of the nonlinear programming variables. In keeping with the naming
630  /// semantics of this function, error controlled integration is not supported
631  /// (though error estimates will be computed for integrators that support that
632  /// feature), which is a minimal requirement for "consistency".
633  /// @warning Users should simulate systems using `Simulator::StepTo()` in
634  /// place of this function (which was created for off-simulation
635  /// purposes), generally.
636  /// @param dt The non-negative integration step to take.
637  /// @throws std::logic_error If the integrator has not been initialized or
638  /// dt is negative **or** if the integrator
639  /// is not operating in fixed step mode.
640  /// @throws std::runtime_error If the integrator was unable to take a step
641  /// of the requested size.
642  /// @sa IntegrateAtMost(), which is designed to be operated by Simulator and
643  /// accounts for publishing and state reinitialization.
644  /// @sa IntegrateWithMultipleSteps(), which is also designed to be operated
645  /// *outside of* Simulator, but will take as many integration steps as
646  /// necessary until time has been stepped forward by @p dt.
647  ///
648  /// This method at a glance:
649  /// - For integrating ODEs/DAEs not using Simulator
650  /// - Fixed step integration (no step size reductions for error control or
651  /// integrator convergence)
652  /// - Takes only a single step forward.
653  void IntegrateWithSingleFixedStep(const T& dt) {
654  if (dt < 0) {
655  throw std::logic_error("IntegrateWithSingleFixedStep() called with a "
656  "negative step size.");
657  }
658  if (!this->get_fixed_step_mode())
659  throw std::logic_error("IntegrateWithSingleFixedStep() requires fixed "
660  "stepping.");
661  if (!Step(dt)) {
662  throw std::runtime_error("Integrator was unable to take a single fixed "
663  "step of the requested size.");
664  }
665 
666  UpdateStepStatistics(dt);
667  }
668 
669  /**
670  * @name Integrator statistics methods.
671  *
672  * @{
673  * These methods allow the caller to manipulate and query integrator
674  * statistics. Generally speaking, the larger the integration step taken, the
675  * faster a simulation will run. These methods allow querying (and resetting)
676  * the integrator statistics as one means of determining how to make
677  * a simulation run faster.
678  */
679  /**
680  * Forget accumulated statistics. These are reset to the values they have
681  * post construction or immediately after `Initialize()`.
682  */
684  actual_initial_step_size_taken_ = nan();
685  smallest_adapted_step_size_taken_ = nan();
686  largest_step_size_taken_ = nan();
687  num_steps_taken_ = 0;
688  num_ode_evals_ = 0;
689  num_shrinkages_from_error_control_ = 0;
690  num_shrinkages_from_substep_failures_ = 0;
691  num_substep_failures_ = 0;
693  }
694 
695  /// Gets the number of failed sub-steps (implying one or more step size
696  /// reductions was required to permit solving the necessary nonlinear system
697  /// of equations).
698  int64_t get_num_substep_failures() const {
699  return num_substep_failures_;
700  }
701 
702  /// Gets the number of step size shrinkages due to sub-step failures (e.g.,
703  /// integrator convergence failures) since the last call to ResetStatistics()
704  /// or Initialize().
706  return num_shrinkages_from_substep_failures_;
707  }
708 
709  /// Gets the number of step size shrinkages due to failure to meet targeted
710  /// error tolerances, since the last call to ResetStatistics or Initialize().
712  return num_shrinkages_from_error_control_;
713  }
714 
715 /**
716  * Returns the number of ODE function evaluations (calls to
717  * CalcTimeDerivatives()) since the last call to ResetStatistics() or
718  * Initialize(). This count includes *all* such calls including (1)
719  * those necessary to compute Jacobian matrices; (2) those used in rejected
720  * integrated steps (for, e.g., purposes of error control); (3) those used
721  * strictly for integrator error estimation; and (4) calls that exhibit little
722  * cost (due to results being cached).
723  */
724  int64_t get_num_derivative_evaluations() const { return num_ode_evals_; }
725 
726  /**
727  * The actual size of the successful first step.
728  */
730  return actual_initial_step_size_taken_;
731  }
732 
733  /**
734  * The size of the smallest step taken *as the result of a controlled
735  * integration step adjustment* since the last Initialize() or
736  * ResetStatistics() call. This value will be NaN for integrators without
737  * error estimation.
738  */
740  return smallest_adapted_step_size_taken_;
741  }
742 
743  /**
744  * The size of the largest step taken since the last Initialize() or
745  * ResetStatistics() call.
746  */
747  const T& get_largest_step_size_taken() const {
748  return largest_step_size_taken_;
749  }
750 
751  /**
752  * The number of integration steps taken since the last Initialize()
753  * or ResetStatistics() call.
754  */
755  int64_t get_num_steps_taken() const { return num_steps_taken_; }
756 
757  /**
758  * @}
759  */
760 
761  /**
762  * Return the step size the integrator would like to take next, based
763  * primarily on the integrator's accuracy prediction. This value will not
764  * be computed for integrators that do not support error estimation and
765  * NaN will be returned.
766  */
767  const T& get_ideal_next_step_size() const { return ideal_next_step_size_; }
768 
769  /**
770  * Returns a const reference to the internally-maintained Context holding
771  * the most recent state in the trajectory. This is suitable for publishing or
772  * extracting information about this trajectory step.
773  */
774  const Context<T>& get_context() const { return *context_; }
775 
776  /**
777  * Returns a mutable pointer to the internally-maintained Context holding
778  * the most recent state in the trajectory.
779  */
780  Context<T>* get_mutable_context() { return context_; }
781 
782  /**
783  * Replace the pointer to the internally-maintained Context with a different
784  * one. This is useful for supplying a new set of initial conditions or
785  * wiping out the current context (by passing in a null pointer). You
786  * should invoke Initialize() after replacing the Context unless the
787  * context is null.
788  * @param context The pointer to the new context or nullptr to wipe out
789  * the current context without replacing it with another.
790  */
791  void reset_context(Context<T>* context) {
792  context_ = context;
793  initialization_done_ = false;
794  }
795 
796 
797  /**
798  * @name Methods for dense output computation
799  * @{
800  *
801  * In general, dense output computations entail both CPU load and memory
802  * footprint increases during numerical integration. For some applications,
803  * the performance penalty may be prohibitive. As such, these computations
804  * are only carried out by explicit user request. The API to start and stop
805  * a _dense integration_ process (i.e. a numerical integration process that
806  * also computes dense output) is consistent with this design choice.
807  */
808 
809  /**
810  * Starts dense integration, allocating a new dense output for this integrator
811  * to use.
812  *
813  * @pre The integrator has been initialized.
814  * @pre The system being integrated has continuous state.
815  * @pre No dense integration is in progress (no dense output is held by the
816  * integrator)
817  * @throw std::logic_error if any of the preconditions is not met.
818  * @warning Dense integration may incur significant overhead.
819  */
821  if (!is_initialized()) {
822  throw std::logic_error("Integrator was not initialized.");
823  }
824  if (get_context().get_continuous_state().size() == 0) {
825  throw std::logic_error("System has no continuous state,"
826  " no dense output can be built.");
827  }
828  if (get_dense_output()) {
829  throw std::logic_error("Dense integration has been started already.");
830  }
831  dense_output_ = DoStartDenseIntegration();
832  }
833 
834  /**
835  * Returns a const pointer to the integrator's current DenseOutput instance,
836  * holding a representation of the continuous state trajectory since the last
837  * StartDenseIntegration() call. This is suitable to query the integrator's
838  * current dense output, if any (may be nullptr).
839  */
841  return dense_output_.get();
842  }
843 
844  /**
845  * Stops dense integration, yielding ownership of the current dense output
846  * to the caller.
847  *
848  * @remarks This process is irreversible.
849  * @return A DenseOutput instance, i.e. a representation of the
850  * continuous state trajectory of the system being integrated
851  * that can be evaluated at any time within its extension. This
852  * representation is defined starting at the context time of the
853  * last StartDenseIntegration() call and finishing at the current
854  * context time.
855  * @pre Dense integration is in progress (a dense output is held by this
856  * integrator, after a call to StartDenseIntegration()).
857  * @post Previously held dense output is not updated nor referenced by
858  * the integrator anymore.
859  * @throw std::logic_error if any of the preconditions is not met.
860  */
861  std::unique_ptr<DenseOutput<T>> StopDenseIntegration() {
862  if (!dense_output_) {
863  throw std::logic_error("No dense integration has been started.");
864  }
865  return std::move(dense_output_);
866  }
867 
868  /**
869  * @}
870  */
871 
872  /**
873  * Gets a constant reference to the system that is being integrated (and
874  * was provided to the constructor of the integrator).
875  */
876  const System<T>& get_system() const { return system_; }
877 
878  /// Indicates whether the integrator has been initialized.
879  bool is_initialized() const { return initialization_done_; }
880 
881  /**
882  * Derived classes must override this function to return the order of
883  * the integrator's error estimate. If the integrator does not provide an
884  * error estimate, the derived class implementation should return 0.
885  */
886  virtual int get_error_estimate_order() const = 0;
887 
888  /**
889  * Gets the size of the last (previous) integration step. If no integration
890  * steps have been taken, value will be NaN.
891  */
893  return prev_step_size_;
894  }
895 
896  /**
897  * Gets the error estimate (used only for integrators that support error
898  * estimation). If the integrator does not support error estimation, nullptr
899  * is returned.
900  */
902  return err_est_.get();
903  }
904 
905  /**
906  * @name Methods for weighting state variable errors
907  * @{
908  * This group of methods describes how errors for state variables with
909  * heterogeneous units are weighted in the context of error-controlled
910  * integration. This is an advanced topic and most users can simply specify
911  * desired accuracy and accept the default state variable weights.
912  *
913  * A collection of state variables is generally defined in heterogenous units
914  * (e.g. length, angles, velocities, energy). Some of the state
915  * variables cannot even be expressed in meaningful units, like
916  * quaternions. Certain integrators provide an estimate of the absolute error
917  * made in each state variable during an integration step. These errors must
918  * be properly weighted to obtain an "accuracy" _with respect to each
919  * particular variable_. These per-variable accuracy determinations can be
920  * compared against the user's requirements and used to select an appropriate
921  * size for the next step [Sherman 2011]. The weights are
922  * normally determined automatically using the system's characteristic
923  * dimensions, so *most users can stop reading now!* Custom weighting is
924  * primarily useful for performance improvement; an optimal weighting would
925  * allow an error-controlled integrator to provide the desired level of
926  * accuracy across all state variables without wasting computation
927  * achieving superfluous accuracy for some of those variables.
928  *
929  * Users interested in more precise control over state variable weighting may
930  * use the methods in this group to access and modify weighting factors for
931  * individual state variables. Changes to these weights can only be made prior
932  * to integrator initialization or as a result of an event being triggered
933  * and then followed by re-initialization.
934  *
935  * <h4>Relative versus absolute accuracy</h4>
936  *
937  * %State variable integration error, as estimated by an integrator, is an
938  * absolute quantity with the same
939  * units as the variable. At each time step we therefore need to determine
940  * an absolute error that would be deemed "good enough", i.e. satisfies
941  * the user's accuracy requirement. If a variable is maintained to a
942  * *relative* accuracy then that "good enough" value is defined to be the
943  * required accuracy `a` (a fraction like 0.001) times the current value of
944  * the variable, as long as that value
945  * is far from zero. For variables maintained to an *absolute* accuracy, or
946  * relative variables that are at or near zero (where relative accuracy would
947  * be undefined or too strict, respectively), we need a different way to
948  * determine the "good enough" absolute error. The methods in this section
949  * control how that absolute error value is calculated.
950  *
951  * <h4>How to choose weights</h4>
952  *
953  * The weight `wᵢ` for a state variable `xᵢ` should be
954  * chosen so that the product `wᵢ * dxᵢ` is unitless, and in particular is 1
955  * when `dxᵢ` represents a "unit effect" of state variable `xᵢ`; that is, the
956  * change in `xᵢ` that produces a unit change in some quantity of interest in
957  * the system being simulated. Why unity (1)? Aside from normalizing the
958  * values, unity "grounds" the weighted error to the user-specified accuracy.
959  * A weighting can be applied individually to each state variable, but
960  * typically it is done approximately by combining the known type of the
961  * variable (e.g. length, angle) with a "characteristic scale" for that
962  * quantity. For example, if a "characteristic length" for the system being
963  * simulated is 0.1 meters, and `x₀` is a length variable measured in meters,
964  * then `w₀` should be 10 so that `w₀*dx₀=1` when `dx₀=0.1`. For angles
965  * representing pointing accuracy (say a camera direction) we typically assume
966  * a "characteristic angle" is one radian (about 60 degrees), so if x₁ is a
967  * pointing direction then w₁=1 is an appropriate weight. We can now scale an
968  * error vector `e=[dx₀ dx₁]` to a unitless fractional error vector
969  * `f=[w₀*dx₀ w₁*dx₁]`. Now to achieve a given accuracy `a`, say `a=.0001`,
970  * we need only check that `|fᵢ|<=a` for each element `i` of `f`. Further,
971  * this gives us a quantitative measure of "worst accuracy" that we can use
972  * to increase or reduce size of the next attempted step, so that we will just
973  * achieve the required accuracy but not much more. We'll be more precise
974  * about this below.
975  *
976  * @anchor quasi_coordinates
977  * <h4>Some subtleties for second-order dynamic systems</h4>
978  *
979  * Systems governed by 2nd-order differential equations are typically split
980  * into second order (configuration) variables q, and rate (velocity)
981  * variables v, where the time derivatives qdot of q are linearly related to
982  * v by the kinematic differential equation `qdot = dq/dt = N(q)*v`.
983  * Velocity variables are
984  * chosen to be physically significant, but configuration variables
985  * may be chosen for convenience and do not necessarily have direct physical
986  * interpretation. For examples, quaternions are chosen as a numerically
987  * stable orientation representation. This is problematic for choosing weights
988  * which must be done by physical reasoning
989  * as sketched above. We resolve this by introducing
990  * the notion of "quasi-coordinates" ꝗ (pronounced "qbar") which are defined
991  * by the equation `ꝗdot = dꝗ/dt = v`. Other than time scaling,
992  * quasi-coordinates have the same units as their corresponding velocity
993  * variables. That is, for weighting we need to think
994  * of the configuration coordinates in the same physical space as the velocity
995  * variables; weight those by their physical significance; and then map back
996  * to an instantaneous weighting
997  * on the actual configuration variables q. This mapping is performed
998  * automatically; you need only to be concerned about physical weightings.
999  *
1000  * Note that generalized quasi-coordinates `ꝗ` can only be defined locally for
1001  * a particular configuration `q`. There is in general no meaningful set of
1002  * `n` generalized
1003  * coordinates which can be differentiated with respect to time to yield `v`.
1004  * For example, the Hairy Ball Theorem implies that it is not possible for
1005  * three orientation variables to represent all 3D rotations without
1006  * singularities, yet three velocity variables can represent angular velocity
1007  * in 3D without singularities.
1008  *
1009  * To summarize, separate weights can be provided for each of
1010  * - `n` generalized quasi-coordinates `ꝗ` (configuration variables in the
1011  * velocity variable space), and
1012  * - `nz` miscellaneous continuous state variables `z`.
1013  *
1014  * Weights on the generalized velocity variables `v (= dꝗ/dt)` are derived
1015  * directly from the weights on `ꝗ`, weighted by a characteristic time.
1016  * Weights on the actual `nq` generalized coordinates can
1017  * be calculated efficiently from weights on the quasi-coordinates (details
1018  * below).
1019  *
1020  * <h4>How the weights are used</h4>
1021  *
1022  * The errors in the `ꝗ` and `z` variables are weighted by the diagonal
1023  * elements
1024  * of diagonal weighting matrices Wꝗ and Wz, respectively. (The block-diagonal
1025  * weighting matrix `Wq` on the original generalized coordinates `q` is
1026  * calculated from `N` and `Wꝗ`; see below.) In the absence of
1027  * other information, the default for all weighting values is one, so `Wꝗ` and
1028  * `Wz` are `n × n` and `nz × nz` identity matrices. The weighting matrix `Wv`
1029  * for the velocity variables is just `Wv = τ*Wꝗ` where `τ` is a
1030  * "characteristic time" for the system, that is, a quantity in time units
1031  * that represents a significant evolution of the trajectory. This serves to
1032  * control the accuracy with which velocity is determined relative to
1033  * configuration. Note that larger values of `τ` are more conservative since
1034  * they increase the velocity weights. Typically we use `τ=1.0` or `0.1`
1035  * seconds for human-scale mechanical systems.
1036  * <!-- TODO(sherm1): provide more guidance for velocity weighting. -->
1037  *
1038  * The weighting matrices `Wq`, `Wv`, and `Wz` are used to compute a weighted
1039  * infinity norm as follows. Although `Wv` and `Wz` are constant, the actual
1040  * weightings may be state dependent for relative-error calculations.
1041  * Define block diagonal error weighting matrix `E=diag(Eq,Ev,Ez)` as follows:
1042  * <pre>
1043  * Eq = Wq
1044  * Ev: Ev(i,i) = { min(Wv(i,i), 1/|vᵢ|) if vᵢ is relative
1045  * { Wv(i,i) if vᵢ is absolute
1046  * Ez: Ez(i,i) = { min(Wz(i,i), 1/|zᵢ|) if zᵢ is relative
1047  * { Wz(i,i) if zᵢ is absolute
1048  * </pre>
1049  * (`Ev` and `Ez` are diagonal.) A `v` or `z` will be maintained to relative
1050  * accuracy unless (a) it is "close" to zero (less than 1), or (b) the
1051  * variable has been defined as requiring absolute accuracy. Position
1052  * variables `q` are always maintained to absolute accuracy (see
1053  * [Sherman 2011] for rationale).
1054  *
1055  * Now given an error estimate vector `e=[eq ev ez]`, the vector `f=E*e`
1056  * can be considered to provide a unitless fractional error for each of the
1057  * state variables. To achieve a given user-specified accuracy `a`, we require
1058  * that norm_inf(`f`) <= `a`. That is, no element of `f` can have absolute
1059  * value larger than `a`. We also use `f` to determine an ideal next step
1060  * size using an appropriate integrator-specific computation.
1061  *
1062  * <h4>Determining weights for q</h4>
1063  *
1064  * The kinematic differential equations `qdot=N(q)*v` employ an `nq × n`
1065  * matrix `N`. By construction, this relationship is invertible using `N`'s
1066  * left pseudo-inverse `N⁺` so that `v=N⁺ qdot` and `N⁺ N = I` (the identity
1067  * matrix); however, `N N⁺ != I`, as `N` has more rows than columns generally.
1068  * [Nikravesh 1988] shows how such a matrix `N` can be determined and provides
1069  * more information. Given this relationship between `N` and `N⁺`, we can
1070  * relate weighted errors in configuration coordinates `q` to weighted errors
1071  * in generalized quasi-coordinates `ꝗ`, as the following derivation shows:
1072  * <pre>
1073  * v = N⁺ qdot Inverse kinematic differential equation
1074  * dꝗ/dt = N⁺ dq/dt Use synonyms for v and qdot
1075  * dꝗ = N⁺ dq Change time derivatives to differentials
1076  * Wꝗ dꝗ = Wꝗ N⁺ dq Pre-multiply both sides by Wꝗ
1077  * N Wꝗ dꝗ = N Wꝗ N⁺ dq Pre-multiply both sides by N
1078  * N Wꝗ dꝗ = Wq dq Define Wq := N Wꝗ N⁺
1079  * N Wꝗ v = Wq qdot Back to time derivatives.
1080  * </pre>
1081  * The last two equations show that `Wq` as defined above provides the
1082  * expected relationship between the weighted `ꝗ` or `v` variables in velocity
1083  * space and the weighted `q` or `qdot` (resp.) variables in configuration
1084  * space.
1085  *
1086  * Finally, note that a diagonal entry of one of the weighting matrices can
1087  * be set to zero to disable error estimation for that state variable
1088  * (i.e., auxiliary variable or configuration/velocity variable pair), but
1089  * that setting an entry to a negative value will cause an exception to be
1090  * thrown when the integrator is initialized.
1091  *
1092  * - [Nikravesh 1988] P. Nikravesh. Computer-Aided Analysis of Mechanical
1093  * Systems. Prentice Hall, 1988. Sec. 6.3.
1094  * - [Sherman 2011] M. Sherman, et al. Procedia IUTAM 2:241-261 (2011),
1095  * Section 3.3. http://dx.doi.org/10.1016/j.piutam.2011.04.023
1096  *
1097  * @sa CalcStateChangeNorm()
1098  */
1099  /**
1100  * Gets the weighting vector (equivalent to a diagonal matrix) applied to
1101  * weighting both generalized coordinate and velocity state variable errors,
1102  * as described in the group documentation. Only used for integrators that
1103  * support error estimation.
1104  */
1105  const Eigen::VectorXd& get_generalized_state_weight_vector() const {
1106  return qbar_weight_;
1107  }
1108 
1109  /**
1110  * Gets a mutable weighting vector (equivalent to a diagonal matrix) applied
1111  * to weighting both generalized coordinate and velocity state variable
1112  * errors, as described in the group documentation. Only used for
1113  * integrators that support error estimation. Returns a VectorBlock
1114  * to make the values mutable without permitting changing the size of
1115  * the vector. Requires re-initializing the integrator after calling
1116  * this method; if Initialize() is not called afterward, an exception will be
1117  * thrown when attempting to call StepOnceAtMost(). If the caller sets
1118  * one of the entries to a negative value, an exception will be thrown
1119  * when the integrator is initialized.
1120  */
1121  Eigen::VectorBlock<Eigen::VectorXd>
1123  initialization_done_ = false;
1124  return qbar_weight_.head(qbar_weight_.rows());
1125  }
1126 
1127  /**
1128  * Gets the weighting vector (equivalent to a diagonal matrix) for
1129  * weighting errors in miscellaneous continuous state variables `z`. Only used
1130  * for integrators that support error estimation.
1131  */
1132  const Eigen::VectorXd& get_misc_state_weight_vector() const {
1133  return z_weight_;
1134  }
1135 
1136  /**
1137  * Gets a mutable weighting vector (equivalent to a diagonal matrix) for
1138  * weighting errors in miscellaneous continuous state variables `z`. Only used
1139  * for integrators that support error estimation. Returns a VectorBlock
1140  * to make the values mutable without permitting changing the size of
1141  * the vector. Requires re-initializing the integrator after calling this
1142  * method. If Initialize() is not called afterward, an exception will be
1143  * thrown when attempting to call StepOnceAtMost(). If the caller sets
1144  * one of the entries to a negative value, an exception will be thrown
1145  * when the integrator is initialized.
1146  */
1147  Eigen::VectorBlock<Eigen::VectorXd> get_mutable_misc_state_weight_vector() {
1148  initialization_done_ = false;
1149  return z_weight_.head(z_weight_.rows());
1150  }
1151 
1152  /**
1153  * @}
1154  */
1155 
1156  protected:
1157  /// Resets any statistics particular to a specific integrator. The default
1158  /// implementation of this function does nothing. If your integrator
1159  /// collects its own statistics, you should re-implement this method and
1160  /// reset them there.
1161  virtual void DoResetStatistics() {}
1162 
1163  /// Evaluates the derivative function (and updates call statistics).
1164  /// Subclasses should call this function rather than calling
1165  /// system.CalcTimeDerivatives() directly.
1166  void CalcTimeDerivatives(const Context<T>& context,
1167  ContinuousState<T>* dxdt) {
1168  get_system().CalcTimeDerivatives(context, dxdt);
1169  ++num_ode_evals_;
1170  }
1171 
1172  /// Evaluates the derivative function (and updates call statistics).
1173  /// Subclasses should call this function rather than calling
1174  /// system.CalcTimeDerivatives() directly. This version of this function
1175  /// exists to allow integrators to count AutoDiff'd systems in derivative
1176  /// function evaluations.
1177  template <typename U>
1178  void CalcTimeDerivatives(const System<U>& system,
1179  const Context<U>& context,
1180  ContinuousState<U>* dxdt) {
1181  system.CalcTimeDerivatives(context, dxdt);
1182  ++num_ode_evals_;
1183  }
1184 
1185  /**
1186  * Sets the working ("in use") accuracy for this integrator. The working
1187  * accuracy may not be equivalent to the target accuracy when the latter is
1188  * too loose or tight for an integrator's capabilities.
1189  * @sa get_accuracy_in_use()
1190  * @sa get_target_accuracy()
1191  */
1192  void set_accuracy_in_use(double accuracy) { accuracy_in_use_ = accuracy; }
1193 
1194  /// Generic code for validating (and resetting, if need be) the integrator
1195  /// working accuracy for error controlled integrators. This method is
1196  /// intended to be called from an integrator's DoInitialize() method.
1197  /// @param default_accuracy a reasonable default accuracy setting for this
1198  /// integrator.
1199  /// @param loosest_accuracy the loosest accuracy that this integrator should
1200  /// support.
1201  /// @param max_step_fraction a fraction of the maximum step size to use when
1202  /// setting the integrator accuracy and the user has not specified
1203  /// accuracy directly.
1204  /// @throws std::logic_error if neither the initial step size target nor
1205  /// the maximum step size has been set.
1206  void InitializeAccuracy(double default_accuracy, double loosest_accuracy,
1207  double max_step_fraction) {
1208  using std::isnan;
1209 
1210  // Set an artificial step size target, if not set already.
1211  if (isnan(this->get_initial_step_size_target())) {
1212  // Verify that maximum step size has been set.
1213  if (isnan(this->get_maximum_step_size()))
1214  throw std::logic_error("Neither initial step size target nor maximum "
1215  "step size has been set!");
1216 
1218  this->get_maximum_step_size() * max_step_fraction);
1219  }
1220 
1221  // Sets the working accuracy to a good value.
1222  double working_accuracy = this->get_target_accuracy();
1223 
1224  // If the user asks for accuracy that is looser than the loosest this
1225  // integrator can provide, use the integrator's loosest accuracy setting
1226  // instead.
1227  if (isnan(working_accuracy)) {
1228  working_accuracy = default_accuracy;
1229  } else {
1230  if (working_accuracy > loosest_accuracy)
1231  working_accuracy = loosest_accuracy;
1232  }
1233  this->set_accuracy_in_use(working_accuracy);
1234  }
1235 
1236  /**
1237  * Default code for advancing the continuous state of the system by a single
1238  * step of @p dt_max (or smaller, depending on error control). This particular
1239  * function is designed to be called directly by an error estimating
1240  * integrator's DoStep() method to effect error-controlled integration.
1241  * The integrator can effect error controlled integration without calling this
1242  * method, if the implementer so chooses, but this default method is expected
1243  * to function well in most circumstances.
1244  * @param[in] dt_max The maximum step size to be taken. The integrator may
1245  * take a smaller step than specified to satisfy accuracy
1246  * requirements, to resolve integrator convergence problems, or
1247  * to respect the integrator's maximum step size.
1248  * @throws std::logic_error if integrator does not support error
1249  * estimation.
1250  * @note This function will shrink the integration step as necessary whenever
1251  * the integrator's DoStep() fails to take the requested step
1252  * e.g., due to integrator convergence failure.
1253  * @returns `true` if the full step of size @p dt_max is taken and `false`
1254  * otherwise (i.e., a smaller step than @p dt_max was taken).
1255  */
1256  bool StepOnceErrorControlledAtMost(const T& dt_max);
1257 
1258  /**
1259  * Computes the infinity norm of a change in continuous state. We use the
1260  * infinity norm to capture the idea that, by providing accuracy requirements,
1261  * the user can indirectly specify error tolerances that act to limit the
1262  * largest error in any state vector component.
1263  * @returns the norm (a non-negative value)
1264  */
1265  T CalcStateChangeNorm(const ContinuousState<T>& dx_state) const;
1266 
1267  /**
1268  * Calculates adjusted integrator step sizes toward keeping state variables
1269  * within error bounds on the next integration step. Note that it is not
1270  * guaranteed that the (possibly) reduced step size will keep state variables
1271  * within error bounds; however, the process of (1) taking a trial
1272  * integration step, (2) calculating the error, and (3) adjusting the step
1273  * size can be repeated until convergence.
1274  * @param err
1275  * The norm of the integrator error that was computed using
1276  * @p attempted_step_size.
1277  * @param attempted_step_size
1278  * The step size that was attempted.
1279  * @param[in,out] at_minimum_step_size
1280  * If `true` on entry, the error control mechanism is not allowed to
1281  * shrink the step because the integrator is stepping at the minimum
1282  * step size (note that this condition will only occur if
1283  * `get_throw_on_minimum_step_size_violation() == false`- an exception
1284  * would be thrown otherwise). If `true` on entry and `false` on exit,
1285  * the error control mechanism has managed to increase the step size
1286  * above the working minimum; if `true` on entry and `true` on exit,
1287  * error control would like to shrink the step size but cannot. If
1288  * `false` on entry and `true` on exit, error control shrank the step
1289  * to the working minimum step size.
1290  * @returns a pair of types bool and T; the bool will be set to `true` if
1291  * the integration step was to be considered successful and `false`
1292  * otherwise. The value of the T type will be set to the recommended next
1293  * step size.
1294  */
1295  std::pair<bool, T> CalcAdjustedStepSize(
1296  const T& err,
1297  const T& attempted_step_size,
1298  bool* at_minimum_step_size) const;
1299 
1300  /**
1301  * Derived classes can override this method to perform special
1302  * initialization. This method is called during the Initialize() method. This
1303  * default method does nothing.
1304  */
1305  virtual void DoInitialize() {}
1306 
1307  /**
1308  * Derived classes can override this method to perform routines when
1309  * Reset() is called. This default method does nothing.
1310  */
1311  virtual void DoReset() {}
1312 
1313  /**
1314  * Derived classes can override this method to provide a continuous
1315  * extension of their own when StartDenseIntegration() is called.
1316  *
1317  * TODO(hidmic): Make pure virtual and override on each subclass, as
1318  * the 'optimal' dense output scheme is only known by the specific
1319  * integration scheme being implemented.
1320  */
1321  virtual
1322  std::unique_ptr<StepwiseDenseOutput<T>> DoStartDenseIntegration() {
1323  return std::make_unique<HermitianDenseOutput<T>>();
1324  }
1325 
1326  /**
1327  * Returns a mutable pointer to the internally-maintained StepwiseDenseOutput
1328  * instance, holding a representation of the continuous state trajectory since
1329  * the last time StartDenseIntegration() was called. This is useful for
1330  * derived classes to update the integrator's current dense output, if any
1331  * (may be nullptr).
1332  */
1334  return dense_output_.get();
1335  }
1336 
1337  /**
1338  * Derived classes must implement this method to (1) integrate the continuous
1339  * portion of this system forward by a single step of size @p dt and
1340  * (2) set the error estimate (via get_mutable_error_estimate()). This
1341  * method is called during the default Step() method.
1342  * @param dt The integration step to take.
1343  * @returns `true` if successful, `false` if the integrator was unable to take
1344  * a single step of size @p dt (due to, e.g., an integrator
1345  * convergence failure).
1346  * @post If the time on entry is denoted `t`, the time and state will be
1347  * advanced to `t+dt` if the method returns `true`; otherwise, the
1348  * time and state should be reset to those at `t`.
1349  * @warning It is expected that DoStep() will return `true` for some, albeit
1350  * possibly very small, positive value of @p dt. The derived
1351  * integrator's stepping algorithm can make this guarantee, for
1352  * example, by switching to an algorithm not subject to convergence
1353  * failures (e.g., explicit Euler) for very small step sizes.
1354  */
1355  virtual bool DoStep(const T& dt) = 0;
1356 
1357  /**
1358  * Derived classes may implement this method to (1) integrate the continuous
1359  * portion of this system forward by a single step of size @p dt, (2) set the
1360  * error estimate (via get_mutable_error_estimate()) and (3) update their own
1361  * dense output implementation (via get_mutable_dense_output()). This method
1362  * is called during the default Step() method.
1363  * @param dt The integration step to take.
1364  * @returns `true` if successful, `false` if either the integrator was
1365  * unable to take a single step of size @p dt or to advance
1366  * its dense output an equal step.
1367  * @sa DoStep()
1368  *
1369  * TODO(hidmic): Make pure virtual and override on each subclass, as
1370  * the 'optimal' dense output scheme is only known by the specific
1371  * integration scheme being implemented.
1372  */
1373  virtual bool DoDenseStep(const T& dt) {
1374  const ContinuousState<T>& state = context_->get_continuous_state();
1375  // Makes a null (i.e. zero size) dense output step with initial
1376  // time and state, before the actual integration step. This will later
1377  // be extended with the final values after the step.
1378  system_.CalcTimeDerivatives(*context_, derivatives_.get());
1380  context_->get_time(), state.CopyToVector(),
1381  derivatives_->CopyToVector());
1382 
1383  // Performs the integration step.
1384  if (!DoStep(dt)) return false;
1385 
1386  // Extends dense output step to the end of the integration step, using
1387  // the post-step values.
1388  system_.CalcTimeDerivatives(*context_, derivatives_.get());
1389  step.Extend(context_->get_time(), state.CopyToVector(),
1390  derivatives_->CopyToVector());
1391 
1392  // Retrieves dense output. This cast is safe if the base implementations
1393  // of this method and DoStartDenseIntegration() are in use. Otherwise, a
1394  // different dense output type may have been allocated and the following
1395  // cast will throw.
1396  HermitianDenseOutput<T>& dense_output =
1398  // Updates dense output with the integration step taken.
1399  dense_output.Update(std::move(step));
1400  return true;
1401  }
1402 
1403  /**
1404  * Gets an error estimate of the state variables recorded by the last call
1405  * to StepOnceFixedSize(). If the integrator does not support error
1406  * estimation, this function will return nullptr.
1407  */
1408  ContinuousState<T>* get_mutable_error_estimate() { return err_est_.get(); }
1409 
1410  // Sets the actual initial step size taken.
1412  actual_initial_step_size_taken_ = dt;
1413  }
1414 
1415  /**
1416  * Sets the size of the smallest-step-taken statistic as the result of a
1417  * controlled integration step adjustment.
1418  */
1420  smallest_adapted_step_size_taken_ = dt;
1421  }
1422 
1423  // Sets the largest-step-size-taken statistic.
1424  void set_largest_step_size_taken(const T& dt) {
1425  largest_step_size_taken_ = dt;
1426  }
1427 
1428  // Sets the "ideal" next step size (typically done via error control).
1429  void set_ideal_next_step_size(const T& dt) { ideal_next_step_size_ = dt; }
1430 
1431  private:
1432  // Validates that a smaller step size does not fall below the working minimum
1433  // and throws an exception if desired.
1434  void ValidateSmallerStepSize(const T& current_step_size,
1435  const T& new_step_size) const {
1436  if (new_step_size < get_working_minimum_step_size() &&
1437  new_step_size < current_step_size && // Verify step adjusted downward.
1438  min_step_exceeded_throws_) {
1439  SPDLOG_DEBUG(drake::log(), "Integrator wants to select too small step "
1440  "size of {}; working minimum is ", new_step_size,
1442  std::ostringstream str;
1443  str << "Error control wants to select step smaller than minimum" <<
1444  " allowed (" << get_working_minimum_step_size() << ")";
1445  throw std::runtime_error(str.str());
1446  }
1447  }
1448 
1449  // Updates the integrator statistics, accounting for a step just taken of
1450  // size dt.
1451  void UpdateStepStatistics(const T& dt) {
1452  // Handle first step specially.
1453  if (++num_steps_taken_ == 1) {
1456  } else {
1458  }
1459 
1460  // Update the previous step size.
1461  prev_step_size_ = dt;
1462  }
1463 
1464  // Steps the system forward exactly by @p dt, if possible, by calling DoStep
1465  // or DoDenseStep depending on whether dense integration was started or not.
1466  // Does necessary pre-initialization and post-cleanup. This method does not
1467  // update general integrator statistics (which are updated in the calling
1468  // methods), because error control might decide that it does not like the
1469  // result of the step and might "rewind" and take a smaller one.
1470  // @returns `true` if successful, `false` otherwise (due to, e.g., integrator
1471  // convergence failure).
1472  // @sa DoStep()
1473  // @sa DoDenseStep()
1474  bool Step(const T& dt) {
1475  if (get_dense_output()) {
1476  return DoDenseStep(dt);
1477  }
1478  return DoStep(dt);
1479  }
1480 
1481  // Reference to the system being simulated.
1482  const System<T>& system_;
1483 
1484  // Pointer to the context.
1485  Context<T>* context_{nullptr}; // The trajectory Context.
1486 
1487  // Current dense output.
1488  std::unique_ptr<StepwiseDenseOutput<T>> dense_output_{nullptr};
1489 
1490  // Runtime variables.
1491  // For variable step integrators, this is set at the end of each step to guide
1492  // the next one.
1493  T ideal_next_step_size_{nan()}; // Indicates that the value is uninitialized.
1494 
1495  // The scaling factor to apply to an integration step size when an integrator
1496  // convergence failure occurs (to make convergence more likely on the next
1497  // attempt).
1498  // TODO(edrumwri): Allow subdivision factor to be user-tweakable.
1499  const double subdivision_factor_{0.5};
1500 
1501  // The accuracy being used.
1502  double accuracy_in_use_{nan()};
1503 
1504  // The maximum step size.
1505  T max_step_size_{nan()};
1506 
1507  // The minimum step size.
1508  T req_min_step_size_{0};
1509 
1510  // The last step taken by the integrator.
1511  T prev_step_size_{nan()};
1512 
1513  // Whether error-controlled integrator is running in fixed step mode. Value
1514  // is irrelevant for integrators without error estimation capabilities.
1515  bool fixed_step_mode_{false};
1516 
1517  // When the minimum step is exceeded, does the integrator throw an exception?
1518  bool min_step_exceeded_throws_{true};
1519 
1520  // Statistics.
1521  T actual_initial_step_size_taken_{nan()};
1522  T smallest_adapted_step_size_taken_{nan()};
1523  T largest_step_size_taken_{nan()};
1524  int64_t num_steps_taken_{0};
1525  int64_t num_ode_evals_{0};
1526  int64_t num_shrinkages_from_error_control_{0};
1527  int64_t num_shrinkages_from_substep_failures_{0};
1528  int64_t num_substep_failures_{0};
1529 
1530  // Applied as diagonal matrices to weight state change variables.
1531  Eigen::VectorXd qbar_weight_, z_weight_;
1532 
1533  // State copy for reversion during error-controlled integration.
1534  VectorX<T> xc0_save_;
1535 
1536  // A continuous state derivatives scratchpad for the default continuous
1537  // extension implementation.
1538  // TODO(hidmic): Remove when DoDenseStep() is made pure virtual.
1539  std::unique_ptr<ContinuousState<T>> derivatives_;
1540 
1541  // The error estimate computed during integration with error control.
1542  std::unique_ptr<ContinuousState<T>> err_est_;
1543 
1544  // The pseudo-inverse of the matrix that converts time derivatives of
1545  // generalized coordinates to generalized velocities, multiplied by the
1546  // change in the generalized coordinates (used in state change norm
1547  // calculations).
1548  mutable std::unique_ptr<VectorBase<T>> pinvN_dq_change_;
1549 
1550  // Vectors used in state change norm calculations.
1551  mutable VectorX<T> unweighted_substate_change_;
1552  mutable std::unique_ptr<VectorBase<T>> weighted_q_change_;
1553 
1554  // Variable for indicating when an integrator has been initialized.
1555  bool initialization_done_{false};
1556 
1557  // This a workaround for an apparent bug in clang 3.8 in which
1558  // defining this as a static constexpr member kNaN failed to instantiate
1559  // properly for the AutoDiffXd instantiation (worked in gcc and MSVC).
1560  // Restore to sanity when some later clang is current.
1561  static constexpr double nan() {
1562  return std::numeric_limits<double>::quiet_NaN();
1563  }
1564 
1565  double target_accuracy_{nan()}; // means "unspecified, use default"
1566  T req_initial_step_size_{nan()}; // means "unspecified, use default"
1567 };
1568 
1569 template <class T>
1571  using std::isnan;
1572  using std::min;
1573 
1574  // Verify that the integrator supports error estimates.
1575  if (!supports_error_estimation()) {
1576  throw std::logic_error("StepOnceErrorControlledAtMost() requires error "
1577  "estimation.");
1578  }
1579 
1580  // Save time, continuous variables, and time derivative because we'll possibly
1581  // revert time and state.
1582  const Context<T>& context = get_context();
1583  const T current_time = context.get_time();
1584  VectorBase<T>& xc =
1585  get_mutable_context()->get_mutable_continuous_state_vector();
1586  xc0_save_ = xc.CopyToVector();
1587 
1588  // Set the step size to attempt.
1589  T step_size_to_attempt = get_ideal_next_step_size();
1590  if (isnan(step_size_to_attempt)) {
1591  // Integrator has not taken a step. Set the current step size to the
1592  // initial step size.
1593  step_size_to_attempt = get_initial_step_size_target();
1594  DRAKE_DEMAND(!isnan(step_size_to_attempt));
1595  }
1596 
1597  // This variable indicates when the integrator has been pushed to its minimum
1598  // step limit. It can only be "true" if minimum step exceptions have been
1599  // suppressed by the user via set_throw_on_minimum_step_size_violation(false),
1600  // and the error control mechanism determines that the step is as low as it
1601  // can go.
1602  bool at_minimum_step_size = false;
1603 
1604  bool step_succeeded = false;
1605  do {
1606  // Constants used to determine whether modifications to the step size are
1607  // close enough to the attempted step size to use the unadjusted originals,
1608  // or (1) whether the step size to be attempted is so small that we should
1609  // consider it to be artifically limited or (2) whether the step size to
1610  // be attempted is sufficiently close to that requested such that the step
1611  // size should be stretched slightly.
1612  const double near_enough_smaller = 0.95;
1613  const double near_enough_larger = 1.001;
1614 
1615  // If we lose more than a small fraction of the step size we wanted
1616  // to take due to a need to stop at dt_max, make a note of that so the
1617  // step size adjuster won't try to grow from the current step.
1618  bool dt_was_artificially_limited = false;
1619  if (dt_max < near_enough_smaller * step_size_to_attempt) {
1620  // dt_max much smaller than current step size.
1621  dt_was_artificially_limited = true;
1622  step_size_to_attempt = dt_max;
1623  } else {
1624  if (dt_max < near_enough_larger * step_size_to_attempt) {
1625  // dt_max is roughly current step. Make it the step size to prevent
1626  // creating a small sliver (the remaining step).
1627  step_size_to_attempt = dt_max;
1628  }
1629  }
1630 
1631  // Limit the current step size.
1632  step_size_to_attempt = min(step_size_to_attempt, get_maximum_step_size());
1633 
1634  // Keep adjusting the integration step size until any integrator
1635  // convergence failures disappear. Note: this loop's correctness is
1636  // predicated on the assumption that an integrator will always converge for
1637  // a sufficiently small, yet nonzero step size.
1638  T adjusted_step_size = step_size_to_attempt;
1639  while (!Step(adjusted_step_size)) {
1640  SPDLOG_DEBUG(drake::log(), "Sub-step failed at {}", adjusted_step_size);
1641  adjusted_step_size *= subdivision_factor_;
1642 
1643  // Note: we could give the user more rope to hang themselves by looking
1644  // for zero rather than machine epsilon, which might be advantageous if
1645  // the user were modeling systems over extremely small time scales.
1646  // However, that issue could be addressed instead by scaling units, and
1647  // using machine epsilon allows failure to be detected much more rapidly.
1648  if (adjusted_step_size < std::numeric_limits<double>::epsilon()) {
1649  throw std::runtime_error("Integrator has been directed to a near zero-"
1650  "length step in order to obtain convergence.");
1651  }
1652  ValidateSmallerStepSize(step_size_to_attempt, adjusted_step_size);
1653  ++num_shrinkages_from_substep_failures_;
1654  ++num_substep_failures_;
1655  }
1656  step_size_to_attempt = adjusted_step_size;
1657 
1658  //--------------------------------------------------------------------
1659  T err_norm = CalcStateChangeNorm(*get_error_estimate());
1660  T next_step_size;
1661  std::tie(step_succeeded, next_step_size) = CalcAdjustedStepSize(
1662  err_norm, step_size_to_attempt, &at_minimum_step_size);
1663  SPDLOG_DEBUG(drake::log(), "Next step size: {}", next_step_size);
1664 
1665  if (step_succeeded) {
1666  // Only update the next step size (retain the previous one) if the
1667  // step size was not artificially limited.
1668  if (!dt_was_artificially_limited)
1669  ideal_next_step_size_ = next_step_size;
1670 
1672  set_actual_initial_step_size_taken(step_size_to_attempt);
1673 
1674  // Record the adapted step size taken.
1676  (step_size_to_attempt < get_smallest_adapted_step_size_taken() &&
1677  step_size_to_attempt < dt_max))
1678  set_smallest_adapted_step_size_taken(step_size_to_attempt);
1679  } else {
1680  ++num_shrinkages_from_error_control_;
1681 
1682  // Set the next step size to attempt.
1683  step_size_to_attempt = next_step_size;
1684 
1685  // Reset the time, state, and time derivative at t0.
1686  get_mutable_context()->set_time(current_time);
1687  xc.SetFromVector(xc0_save_);
1688  if (get_dense_output()) {
1689  // Take dense output one step back to undo
1690  // the last integration step.
1691  get_mutable_dense_output()->Rollback();
1692  }
1693  }
1694  } while (!step_succeeded);
1695  return (step_size_to_attempt == dt_max);
1696 }
1697 
1698 template <class T>
1700  const ContinuousState<T>& dx_state) const {
1701  using std::max;
1702  const Context<T>& context = get_context();
1703  const auto& system = get_system();
1704 
1705  // Get weighting matrices.
1706  const auto& qbar_v_weight = this->get_generalized_state_weight_vector();
1707  const auto& z_weight = this->get_misc_state_weight_vector();
1708 
1709  // Get the differences in the generalized position, velocity, and
1710  // miscellaneous continuous state vectors.
1711  const VectorBase<T>& dgq = dx_state.get_generalized_position();
1712  const VectorBase<T>& dgv = dx_state.get_generalized_velocity();
1713  const VectorBase<T>& dgz = dx_state.get_misc_continuous_state();
1714 
1715  // (re-)Initialize pinvN_dq_change_ and weighted_q_change_, if necessary.
1716  // Reinitialization might be required if the system state variables can
1717  // change during the course of the simulation.
1718  if (pinvN_dq_change_ == nullptr) {
1719  pinvN_dq_change_ = std::make_unique<BasicVector<T>>(dgv.size());
1720  weighted_q_change_ = std::make_unique<BasicVector<T>>(dgq.size());
1721  }
1722  DRAKE_DEMAND(pinvN_dq_change_->size() == dgv.size());
1723  DRAKE_DEMAND(weighted_q_change_->size() == dgq.size());
1724 
1725  // TODO(edrumwri): Acquire characteristic time properly from the system
1726  // (i.e., modify the System to provide this value).
1727  const double characteristic_time = 1.0;
1728 
1729  // Computes the infinity norm of the weighted velocity variables.
1730  unweighted_substate_change_ = dgv.CopyToVector();
1731  T v_nrm = qbar_v_weight.cwiseProduct(unweighted_substate_change_).
1732  template lpNorm<Eigen::Infinity>() * characteristic_time;
1733 
1734  // Compute the infinity norm of the weighted auxiliary variables.
1735  unweighted_substate_change_ = dgz.CopyToVector();
1736  T z_nrm = (z_weight.cwiseProduct(unweighted_substate_change_))
1737  .template lpNorm<Eigen::Infinity>();
1738 
1739  // Compute N * Wq * dq = N * Wꝗ * N+ * dq.
1740  unweighted_substate_change_ = dgq.CopyToVector();
1741  system.MapQDotToVelocity(context, unweighted_substate_change_,
1742  pinvN_dq_change_.get());
1743  system.MapVelocityToQDot(
1744  context, qbar_v_weight.cwiseProduct(pinvN_dq_change_->CopyToVector()),
1745  weighted_q_change_.get());
1746  T q_nrm = weighted_q_change_->CopyToVector().
1747  template lpNorm<Eigen::Infinity>();
1748  SPDLOG_DEBUG(drake::log(), "dq norm: {}, dv norm: {}, dz norm: {}",
1749  q_nrm, v_nrm, z_nrm);
1750 
1751  // TODO(edrumwri): Record the worst offender (which of the norms resulted
1752  // in the largest value).
1753  // Infinity norm of the concatenation of multiple vectors is equal to the
1754  // maximum of the infinity norms of the individual vectors.
1755  return max(z_nrm, max(q_nrm, v_nrm));
1756 }
1757 
1758 template <class T>
1760  const T& err,
1761  const T& step_taken,
1762  bool* at_minimum_step_size) const {
1763  using std::pow;
1764  using std::min;
1765  using std::max;
1766  using std::isnan;
1767  using std::isinf;
1768 
1769  // Magic numbers come from Simbody.
1770  const double kSafety = 0.9;
1771  const double kMinShrink = 0.1;
1772  const double kMaxGrow = 5.0;
1773  const double kHysteresisLow = 0.9;
1774  const double kHysteresisHigh = 1.2;
1775 
1776  // Get the order for the integrator's error estimate.
1777  const int err_order = get_error_estimate_order();
1778 
1779  // Set value for new step size to invalid value initially.
1780  T new_step_size(-1);
1781 
1782  // First, make a guess at the next step size to use based on
1783  // the supplied error norm. Watch out for NaN. Further adjustments will be
1784  // made in blocks of code that follow.
1785  if (isnan(err) || isinf(err)) // e.g., integrand returned NaN.
1786  new_step_size = kMinShrink * step_taken;
1787  else if (err == 0) // A "perfect" step; can happen if no dofs for example.
1788  new_step_size = kMaxGrow * step_taken;
1789  else // Choose best step for skating just below the desired accuracy.
1790  new_step_size = kSafety * step_taken *
1791  pow(get_accuracy_in_use() / err, 1.0 / err_order);
1792 
1793  // Error indicates that the step size can be increased.
1794  if (new_step_size > step_taken) {
1795  // If the integrator has been directed down to the minimum step size, but
1796  // now error indicates that the step size can be increased, de-activate
1797  // at_minimum_step_size.
1798  *at_minimum_step_size = false;
1799 
1800  // If the new step is bigger than the old, don't make the change if the
1801  // old one was small for some unimportant reason (like reached a publishing
1802  // interval). Also, don't grow the step size if the change would be very
1803  // small; better to keep the step size stable in that case (maybe just
1804  // for aesthetic reasons).
1805  if (new_step_size < kHysteresisHigh * step_taken)
1806  new_step_size = step_taken;
1807  }
1808 
1809  // If error indicates that we should shrink the step size but are not allowed
1810  // to, quit and indicate that the step was successful.
1811  if (new_step_size < step_taken && *at_minimum_step_size) {
1812  return std::make_pair(true, step_taken);
1813  }
1814 
1815  // If we're supposed to shrink the step size but the one we have actually
1816  // achieved the desired accuracy last time, we won't change the step now.
1817  // Otherwise, if we are going to shrink the step, let's not be shy -- we'll
1818  // shrink it by at least a factor of kHysteresisLow.
1819  if (new_step_size < step_taken) {
1820  if (err <= get_accuracy_in_use()) {
1821  new_step_size = step_taken; // not this time
1822  } else {
1823  T test_value = kHysteresisLow * step_taken;
1824  new_step_size = min(new_step_size, test_value);
1825  }
1826  }
1827 
1828  // Keep the size change within the allowable bounds.
1829  T max_grow_step = kMaxGrow * step_taken;
1830  T min_shrink_step = kMinShrink * step_taken;
1831  new_step_size = min(new_step_size, max_grow_step);
1832  new_step_size = max(new_step_size, min_shrink_step);
1833 
1834  // Apply user-requested limits on min and max step size.
1835  // TODO(edrumwri): Introduce some feedback to the user when integrator wants
1836  // to take a smaller step than user has selected as the minimum. Options for
1837  // this feedback could include throwing a special exception, logging, setting
1838  // a flag in the integrator that allows throwing an exception, or returning
1839  // a special status from IntegrateAtMost().
1840  if (!isnan(get_maximum_step_size()))
1841  new_step_size = min(new_step_size, get_maximum_step_size());
1842  ValidateSmallerStepSize(step_taken, new_step_size);
1843 
1844  // Increase the next step size, as necessary.
1845  new_step_size = max(new_step_size, get_working_minimum_step_size());
1846  if (new_step_size == get_working_minimum_step_size()) {
1847  // Indicate that the step is integrator is now trying the minimum step
1848  // size.
1849  *at_minimum_step_size = true;
1850 
1851  // If the integrator wants to shrink the step size below the
1852  // minimum allowed and exceptions are suppressed, indicate that status.
1853  if (new_step_size < step_taken)
1854  return std::make_pair(false, new_step_size);
1855  }
1856 
1857  return std::make_pair(new_step_size >= step_taken, new_step_size);
1858 }
1859 
1860 template <class T>
1862  const T& publish_dt, const T& update_dt, const T& boundary_dt) {
1863 
1865  throw std::logic_error("Integrator not initialized.");
1866 
1867  // Now that integrator has been checked for initialization, get the current
1868  // time.
1869  const T t0 = context_->get_time();
1870 
1871  // Verify that dt's are non-negative.
1872  if (update_dt < 0.0)
1873  throw std::logic_error("Update dt is negative.");
1874  if (publish_dt < 0.0)
1875  throw std::logic_error("Publish dt is negative.");
1876  if (boundary_dt < 0.0)
1877  throw std::logic_error("Boundary dt is negative.");
1878 
1879  // The size of the integration step is the minimum of the time until the next
1880  // update event, the time until the next publish event, the boundary time
1881  // (i.e., the maximum time that the user wished to step to), and the maximum
1882  // step size (which may stretch slightly to hit a discrete event).
1883 
1884  // We report to the caller which event ultimately constrained the step size.
1885  // If multiple events constrained it equally, we prefer to report update
1886  // events over publish events, publish events over boundary step limits,
1887  // and boundary limits over maximum step size limits. The caller must
1888  // determine event simultaneity by inspecting the time.
1889 
1890  // The maintainer of this code is advised to consider that, while updates
1891  // and boundary times, may both conceptually be deemed events, the distinction
1892  // is made for a reason. If both an update and a boundary time occur
1893  // simultaneously, the following behavior should result:
1894  // (1) kReachedUpdateTime is returned, (2) Simulator::StepTo() performs the
1895  // necessary update, (3) IntegrateAtMost() is called with boundary_dt=0 and
1896  // returns kReachedBoundaryTime, and (4) the simulation terminates. This
1897  // sequence of operations will ensure that the simulation state is valid if
1898  // Simulator::StepTo() is called again to advance time further.
1899 
1900  // We now analyze the following simultaneous cases with respect to Simulator:
1901  //
1902  // { publish, update }
1903  // kReachedUpdateTime will be returned, an update will be followed by a
1904  // publish.
1905  //
1906  // { publish, update, max step }
1907  // kReachedUpdateTime will be returned, an update will be followed by a
1908  // publish.
1909  //
1910  // { publish, boundary time, max step }
1911  // kReachedPublishTime will be returned, a publish will be performed followed
1912  // by another call to this function, which should return kReachedBoundaryTime
1913  // (followed in rapid succession by StepTo(.) return).
1914  //
1915  // { publish, boundary time, max step }
1916  // kReachedPublishTime will be returned, a publish will be performed followed
1917  // by another call to this function, which should return kReachedBoundaryTime
1918  // (followed in rapid succession by StepTo(.) return).
1919  //
1920  // { publish, update, boundary time, maximum step size }
1921  // kUpdateTimeReached will be returned, an update followed by a publish
1922  // will then be performed followed by another call to this function, which
1923  // should return kReachedBoundaryTime (followed in rapid succession by
1924  // StepTo(.) return).
1925 
1926  // By default, the candidate dt is the next discrete update event.
1928  T dt = update_dt;
1929 
1930  // If the next discrete publish event is sooner than the next discrete update
1931  // event, the publish event becomes the candidate dt
1932  if (publish_dt < update_dt) {
1933  candidate_result = IntegratorBase<T>::kReachedPublishTime;
1934  dt = publish_dt;
1935  }
1936 
1937  // If the stop time (boundary time) is sooner than the candidate, use it
1938  // instead.
1939  if (boundary_dt < dt) {
1940  candidate_result = IntegratorBase<T>::kReachedBoundaryTime;
1941  dt = boundary_dt;
1942  }
1943 
1944  // If there is no continuous state, there will be no need to limit the
1945  // integration step size.
1946  if (get_context().get_continuous_state().size() == 0) {
1947  Context<T>* context = get_mutable_context();
1948  context->set_time(context->get_time() + dt);
1949  return candidate_result;
1950  }
1951 
1952  // If all events are farther into the future than the maximum step
1953  // size times a stretch factor of 1.01, the maximum step size becomes the
1954  // candidate dt. Put another way, if the maximum step occurs right before
1955  // an update or a publish, the update or publish is done instead. In contrast,
1956  // we never step past boundary_dt, even if doing so would allow hitting a
1957  // publish or an update.
1958  const bool reached_boundary =
1959  (candidate_result == IntegratorBase<T>::kReachedBoundaryTime);
1960  const T& max_dt = IntegratorBase<T>::get_maximum_step_size();
1961  if ((reached_boundary && max_dt < dt) ||
1962  (!reached_boundary && max_dt * get_stretch_factor() < dt)) {
1963  candidate_result = IntegratorBase<T>::kTimeHasAdvanced;
1964  dt = max_dt;
1965  }
1966 
1967  if (dt < 0.0) throw std::logic_error("Negative dt.");
1968 
1969  // If error control is disabled, call the generic stepper. Otherwise, use
1970  // the error controlled method.
1971  bool full_step = true;
1972  if (this->get_fixed_step_mode()) {
1973  T adjusted_dt = dt;
1974  while (!Step(adjusted_dt)) {
1975  ++num_shrinkages_from_substep_failures_;
1976  ++num_substep_failures_;
1977  adjusted_dt *= subdivision_factor_;
1978  ValidateSmallerStepSize(dt, adjusted_dt);
1979  full_step = false;
1980  }
1981  } else {
1982  full_step = StepOnceErrorControlledAtMost(dt);
1983  }
1984  if (get_dense_output()) {
1985  // Consolidates current dense output, merging the step
1986  // taken into its internal representation.
1987  get_mutable_dense_output()->Consolidate();
1988  }
1989 
1990  // Update generic statistics.
1991  const T actual_dt = context_->get_time() - t0;
1992  UpdateStepStatistics(actual_dt);
1993 
1994  if (full_step) {
1995  // If the integrator took the entire maximum step size we allowed above,
1996  // we report to the caller that a step constraint was hit, which may
1997  // indicate a discrete event has arrived.
1998  return candidate_result;
1999  } else {
2000  // Otherwise, we report to the caller that time has advanced, but no
2001  // discrete event has arrived.
2003  }
2004 }
2005 
2006 } // namespace systems
2007 } // namespace drake
void CalcTimeDerivatives(const System< U > &system, const Context< U > &context, ContinuousState< U > *dxdt)
Evaluates the derivative function (and updates call statistics).
Definition: integrator_base.h:1178
T 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&#39;s context.
Definition: integrator_base.h:400
virtual int size() const =0
Returns the number of elements in the vector.
double get_target_accuracy() const
Gets the target accuracy.
Definition: integrator_base.h:255
void set_largest_step_size_taken(const T &dt)
Definition: integrator_base.h:1424
void CalcTimeDerivatives(const Context< T > &context, ContinuousState< T > *dxdt)
Evaluates the derivative function (and updates call statistics).
Definition: integrator_base.h:1166
bool isnan(const Eigen::AutoDiffScalar< DerType > &x)
Overloads isnan to mimic std::isnan from <cmath>.
Definition: autodiff_overloads.h:52
VectorX< T > CopyToVector() const
Returns a copy of the entire continuous state vector into an Eigen vector.
Definition: continuous_state.h:227
Localized an event; this is the before state (interpolated).
Definition: integrator_base.h:143
void set_ideal_next_step_size(const T &dt)
Definition: integrator_base.h:1429
const Eigen::VectorXd & get_generalized_state_weight_vector() const
Gets the weighting vector (equivalent to a diagonal matrix) applied to weighting both generalized coo...
Definition: integrator_base.h:1105
const T & get_actual_initial_step_size_taken() const
The actual size of the successful first step.
Definition: integrator_base.h:729
virtual void DoReset()
Derived classes can override this method to perform routines when Reset() is called.
Definition: integrator_base.h:1311
#define SPDLOG_DEBUG(logger,...)
Definition: text_logging.h:136
Definition: automotive_demo.cc:90
Context< T > * get_mutable_context()
Returns a mutable pointer to the internally-maintained Context holding the most recent state in the t...
Definition: integrator_base.h:780
const T & get_previous_integration_step_size() const
Gets the size of the last (previous) integration step.
Definition: integrator_base.h:892
void Initialize()
An integrator must be initialized before being used.
Definition: integrator_base.h:462
double get_stretch_factor() const
Gets the stretch factor (> 1), which is multiplied by the maximum (typically user-designated) integra...
Definition: integrator_base.h:576
void InitializeAccuracy(double default_accuracy, double loosest_accuracy, double max_step_fraction)
Generic code for validating (and resetting, if need be) the integrator working accuracy for error con...
Definition: integrator_base.h:1206
Context is an abstract class template that represents all the typed values that are used in a System&#39;...
Definition: context.h:41
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorX
A column vector of any size, templated on scalar type.
Definition: eigen_types.h:46
A DenseOutput class interface extension, geared towards step-wise construction procedures.
Definition: stepwise_dense_output.h:25
VectorBase is an abstract base class that real-valued signals between Systems and real-valued System ...
Definition: vector_base.h:27
A StepwiseDenseOutput class implementation using Hermitian interpolators, and therefore a continuous ...
Definition: hermitian_dense_output.h:94
Eigen::VectorBlock< Eigen::VectorXd > get_mutable_generalized_state_weight_vector()
Gets a mutable weighting vector (equivalent to a diagonal matrix) applied to weighting both generaliz...
Definition: integrator_base.h:1122
void StartDenseIntegration()
Starts dense integration, allocating a new dense output for this integrator to use.
Definition: integrator_base.h:820
const VectorBase< T > & get_misc_continuous_state() const
Returns a const reference to the subset of the continuous state vector that is other continuous state...
Definition: continuous_state.h:197
void set_accuracy_in_use(double accuracy)
Sets the working ("in use") accuracy for this integrator.
Definition: integrator_base.h:1192
void set_throw_on_minimum_step_size_violation(bool throws)
Sets whether the integrator should throw a std::runtime_error exception when the integrator&#39;s step si...
Definition: integrator_base.h:381
logging::logger * log()
Retrieve an instance of a logger to use for logging; for example: drake::log()->info("potato!") ...
Definition: text_logging.cc:38
virtual std::unique_ptr< StepwiseDenseOutput< T > > DoStartDenseIntegration()
Derived classes can override this method to provide a continuous extension of their own when StartDen...
Definition: integrator_base.h:1322
void request_initial_step_size_target(const T &step_size)
Request that the first attempted integration step have a particular size.
Definition: integrator_base.h:519
void set_maximum_step_size(const T &max_step_size)
Sets the maximum step size that may be taken by this integrator.
Definition: integrator_base.h:271
const Context< T > & get_context() const
Returns a const reference to the internally-maintained Context holding the most recent state in the t...
Definition: integrator_base.h:774
An integration step representation class, holding just enough for Hermitian interpolation: three (3) ...
Definition: hermitian_dense_output.h:111
virtual VectorX< T > CopyToVector() const
Copies the entire state to a vector with no semantics.
Definition: vector_base.h:98
void IntegrateWithSingleFixedStep(const T &dt)
Stepping function for integrators operating outside of Simulator that advances the continuous state e...
Definition: integrator_base.h:653
ContinuousState< T > * get_mutable_error_estimate()
Gets an error estimate of the state variables recorded by the last call to StepOnceFixedSize().
Definition: integrator_base.h:1408
const T & get_initial_step_size_target() const
Gets the target size of the first integration step.
Definition: integrator_base.h:534
#define DRAKE_ASSERT(condition)
DRAKE_ASSERT(condition) is similar to the built-in assert(condition) from the C++ system header <cas...
Definition: drake_assert.h:37
bool get_fixed_step_mode() const
Gets whether an integrator is running in fixed step mode.
Definition: integrator_base.h:213
StepResult
Status returned by StepOnceAtMost().
Definition: integrator_base.h:135
const ContinuousState< T > * get_error_estimate() const
Gets the error estimate (used only for integrators that support error estimation).
Definition: integrator_base.h:901
virtual void set_time(const T &time_sec)
Set the current time in seconds.
Definition: context.h:67
User requested control whenever an internal step is successful.
Definition: integrator_base.h:151
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...
Definition: integrator_base.h:1570
Provides Drake&#39;s assertion implementation.
This is the entry point for all text logging within Drake.
Expression max(const Expression &e1, const Expression &e2)
Definition: symbolic_expression.cc:711
virtual bool DoDenseStep(const T &dt)
Derived classes may implement this method to (1) integrate the continuous portion of this system forw...
Definition: integrator_base.h:1373
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 to...
Definition: integrator_base.h:1861
Took maximum number of steps without finishing integrating over the interval.
Definition: integrator_base.h:158
StepwiseDenseOutput< T > * get_mutable_dense_output()
Returns a mutable pointer to the internally-maintained StepwiseDenseOutput instance, holding a representation of the continuous state trajectory since the last time StartDenseIntegration() was called.
Definition: integrator_base.h:1333
#define DRAKE_DEMAND(condition)
Evaluates condition and iff the value is false will trigger an assertion failure with a message showi...
Definition: drake_assert.h:45
int64_t get_num_derivative_evaluations() const
Returns the number of ODE function evaluations (calls to CalcTimeDerivatives()) since the last call t...
Definition: integrator_base.h:724
const System< T > & get_system() const
Gets a constant reference to the system that is being integrated (and was provided to the constructor...
Definition: integrator_base.h:876
Expression min(const Expression &e1, const Expression &e2)
Definition: symbolic_expression.cc:699
void set_fixed_step_mode(bool flag)
Sets an integrator with error control to fixed step mode.
Definition: integrator_base.h:198
Reached the desired integration time without reaching an update time.
Definition: integrator_base.h:155
void Reset()
Resets the integrator to initial values, i.e., default construction values.
Definition: integrator_base.h:413
void set_actual_initial_step_size_taken(const T &dt)
Definition: integrator_base.h:1411
const T & get_ideal_next_step_size() const
Return the step size the integrator would like to take next, based primarily on the integrator&#39;s accu...
Definition: integrator_base.h:767
const T & get_time() const
Returns the current time in seconds.
Definition: context.h:64
double get_accuracy_in_use() const
Gets the accuracy in use by the integrator.
Definition: integrator_base.h:262
const T & get_maximum_step_size() const
Gets the maximum step size that may be taken by this integrator.
Definition: integrator_base.h:283
std::unique_ptr< DenseOutput< T > > StopDenseIntegration()
Stops dense integration, yielding ownership of the current dense output to the caller.
Definition: integrator_base.h:861
const VectorBase< T > & get_generalized_position() const
Returns a const reference to the subset of the state vector that is generalized position q...
Definition: continuous_state.h:173
Base class for all System functionality that is dependent on the templatized scalar type T for input...
Definition: input_port_descriptor.h:12
const Eigen::VectorXd & get_misc_state_weight_vector() const
Gets the weighting vector (equivalent to a diagonal matrix) for weighting errors in miscellaneous con...
Definition: integrator_base.h:1132
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.
Definition: integrator_base.h:360
virtual void SetFromVector(const Eigen::Ref< const VectorX< T >> &value)
Replaces the entire vector with the contents of value.
Definition: vector_base.h:80
virtual ~IntegratorBase()=default
Destructor.
int64_t get_num_steps_taken() const
The number of integration steps taken since the last Initialize() or ResetStatistics() call...
Definition: integrator_base.h:755
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 t...
Definition: integrator_base.h:739
An interface for dense output of ODE and DAE solutions, to efficiently approximate them at arbitraril...
Definition: dense_output.h:36
virtual void DoInitialize()
Derived classes can override this method to perform special initialization.
Definition: integrator_base.h:1305
void CalcTimeDerivatives(const Context< T > &context, ContinuousState< T > *derivatives) const
Calculates the time derivatives xcdot of the continuous state xc.
Definition: system.h:579
T CalcStateChangeNorm(const ContinuousState< T > &dx_state) const
Computes the infinity norm of a change in continuous state.
Definition: integrator_base.h:1699
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 failur...
Definition: integrator_base.h:705
void IntegrateWithMultipleSteps(const T &dt)
Stepping function for integrators operating outside of Simulator that advances the continuous state e...
Definition: integrator_base.h:600
Indicates that integration terminated at an update time.
Definition: integrator_base.h:147
void reset_context(Context< T > *context)
Replace the pointer to the internally-maintained Context with a different one.
Definition: integrator_base.h:791
const double epsilon
Definition: unrevised_lemke_solver_test.cc:13
void Update(IntegrationStep step)
Update output with the given step.
Definition: hermitian_dense_output.h:294
virtual bool supports_error_estimation() const =0
Indicates whether an integrator supports error estimation.
IntegratorBase(const System< T > &system, Context< T > *context=nullptr)
Maintains references to the system being integrated and the context used to specify the initial condi...
Definition: integrator_base.h:174
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().
Definition: integrator_base.h:711
bool get_throw_on_minimum_step_size_violation() const
Reports the current setting of the throw_on_minimum_step_size_violation flag.
Definition: integrator_base.h:390
virtual bool DoStep(const T &dt)=0
Derived classes must implement this method to (1) integrate the continuous portion of this system for...
virtual void DoResetStatistics()
Resets any statistics particular to a specific integrator.
Definition: integrator_base.h:1161
Eigen::VectorBlock< Eigen::VectorXd > get_mutable_misc_state_weight_vector()
Gets a mutable weighting vector (equivalent to a diagonal matrix) for weighting errors in miscellaneo...
Definition: integrator_base.h:1147
const VectorBase< T > & get_generalized_velocity() const
Returns a const reference to the subset of the continuous state vector that is generalized velocity v...
Definition: continuous_state.h:185
An abstract class for an integrator for ODEs and DAEs as represented by a Drake System.
Definition: integrator_base.h:119
bool is_initialized() const
Indicates whether the integrator has been initialized.
Definition: integrator_base.h:879
ContinuousState is a view of, and optionally a container for, all the continuous state variables xc o...
Definition: continuous_state.h:76
bool isinf(const Eigen::AutoDiffScalar< DerType > &x)
Overloads isinf to mimic std::isinf from <cmath>.
Definition: autodiff_overloads.h:45
Polynomial< CoefficientType > pow(const Polynomial< CoefficientType > &base, typename Polynomial< CoefficientType >::PowerType exponent)
Provides power function for Polynomial.
Definition: polynomial.h:449
const T & get_requested_minimum_step_size() const
Gets the requested minimum step size h_min for this integrator.
Definition: integrator_base.h:370
#define DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN deletes the special member functions for copy-construction, copy-assignment, move-construction, and move-assignment.
Definition: drake_copyable.h:33
virtual int get_error_estimate_order() const =0
Derived classes must override this function to return the order of the integrator&#39;s error estimate...
const DenseOutput< T > * get_dense_output() const
Returns a const pointer to the integrator&#39;s current DenseOutput instance, holding a representation of...
Definition: integrator_base.h:840
void set_target_accuracy(double accuracy)
Request that the integrator attempt to achieve a particular accuracy for the continuous portions of t...
Definition: integrator_base.h:242
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 n...
Definition: integrator_base.h:1759
Indicates a publish time has been reached but not an update time.
Definition: integrator_base.h:139
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...
Definition: integrator_base.h:698
void ResetStatistics()
Forget accumulated statistics.
Definition: integrator_base.h:683
Provides careful macros to selectively enable or disable the special member functions for copy-constr...
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 adj...
Definition: integrator_base.h:1419
const T & get_largest_step_size_taken() const
The size of the largest step taken since the last Initialize() or ResetStatistics() call...
Definition: integrator_base.h:747