Drake
Simulator< T > Class Template Reference

A forward dynamics solver for hybrid dynamic systems represented by System<T> objects. More...

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

Public Member Functions

 Simulator (const System< T > &system, std::unique_ptr< Context< T >> context=nullptr)
 Create a Simulator that can advance a given System through time to produce a trajectory consisting of a sequence of Context values. More...
 
void Initialize ()
 Prepares the Simulator for a simulation. More...
 
void StepTo (const T &boundary_time)
 Advance the System's trajectory until boundary_time is reached in the context or some other termination condition occurs. More...
 
void set_target_realtime_rate (double realtime_rate)
 Slow the simulation down to approximately synchronize with real time when it would otherwise run too fast. More...
 
double get_target_realtime_rate () const
 Return the real time rate target currently in effect. More...
 
double get_actual_realtime_rate () const
 Return the rate that simulated time has progressed relative to real time. More...
 
void set_publish_every_time_step (bool publish)
 Sets whether the simulation should invoke Publish on the System under simulation during every time step. More...
 
void set_publish_at_initialization (bool publish)
 Sets whether the simulation should invoke Publish in Initialize(). More...
 
bool get_publish_every_time_step () const
 Returns true if the simulation should invoke Publish on the System under simulation every time step. More...
 
const Context< T > & get_context () const
 Returns a const reference to the internally-maintained Context holding the most recent step in the trajectory. More...
 
Context< T > * get_mutable_context ()
 Returns a mutable pointer to the internally-maintained Context holding the most recent step in the trajectory. More...
 
void reset_context (std::unique_ptr< Context< T >> context)
 Replace the internally-maintained Context with a different one. More...
 
std::unique_ptr< Context< T > > release_context ()
 Transfer ownership of this Simulator's internal Context to the caller. More...
 
void ResetStatistics ()
 Forget accumulated statistics. More...
 
int64_t get_num_publishes () const
 Gets the number of publishes made since the last Initialize() or ResetStatistics() call. More...
 
int64_t get_num_steps_taken () const
 Gets the number of integration steps since the last Initialize() call. More...
 
int64_t get_num_discrete_updates () const
 Gets the number of discrete variable updates performed since the last Initialize() call. More...
 
int64_t get_num_unrestricted_updates () const
 Gets the number of "unrestricted" updates performed since the last Initialize() call. More...
 
const IntegratorBase< T > * get_integrator () const
 Gets a pointer to the integrator used to advance the continuous aspects of the system. More...
 
IntegratorBase< T > * get_mutable_integrator ()
 Gets a pointer to the mutable integrator used to advance the continuous aspects of the system. More...
 
template<class U , typename... Args>
U * reset_integrator (Args &&...args)
 Resets the integrator with a new one. More...
 
optional< T > GetCurrentWitnessTimeIsolation () const
 Gets the length of the interval used for witness function time isolation. More...
 
const System< T > & get_system () const
 Gets a constant reference to the system. More...
 
Does not allow copy, move, or assignment
 Simulator (const Simulator &)=delete
 
Simulatoroperator= (const Simulator &)=delete
 
 Simulator (Simulator &&)=delete
 
Simulatoroperator= (Simulator &&)=delete
 

Detailed Description

template<typename T>
class drake::systems::Simulator< T >

A forward dynamics solver for hybrid dynamic systems represented by System<T> objects.

Starting with an initial Context for a given System, Simulator advances time and produces a series of Context values that forms a trajectory satisfying the system's dynamic equations to a specified accuracy. Only the Context is modified by a Simulator; the System is const.

A Drake System is a continuous/discrete/hybrid dynamic system where the continuous part is a DAE, that is, it is expected to consist of a set of differential equations and bilateral algebraic constraints. The set of active constraints may change as a result of particular events, such as contact.

Given a current Context, we expect a System to provide us with

  • derivatives for the continuous differential equations that already satisfy the differentiated form of the constraints (typically, acceleration constraints),
  • a projection method for least-squares correction of violated higher-level constraints (position and velocity level),
  • a time-of-next-update method that can be used to adjust the integrator step size in preparation for a discrete update,
  • a method that can update discrete variables when their update time is reached,
  • witness (guard) functions for event isolation,
  • event handlers (reset functions) for making appropriate changes to state and mode variables when an event has been isolated.

The continuous parts of the trajectory are advanced using a numerical integrator. Different integrators have different properties; if you know about that you can choose the one that is most appropriate for your application. Otherwise, a default is provided which is adequate for most systems.

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

Instantiated templates for the following kinds of T's are provided and available to link against in the containing library:

  • double
  • AutoDiffXd

Other instantiations are permitted but take longer to compile.

Constructor & Destructor Documentation

Simulator ( const Simulator< T > &  )
delete
Simulator ( Simulator< T > &&  )
delete
Simulator ( const System< T > &  system,
std::unique_ptr< Context< T >>  context = nullptr 
)
explicit

Create a Simulator that can advance a given System through time to produce a trajectory consisting of a sequence of Context values.

The System must not have unresolved input ports if the values of those ports are necessary for computations performed during simulation (see class documentation).

The Simulator holds an internal, non-owned reference to the System object so you must ensure that system has a longer lifetime than the Simulator. It also owns a compatible Context internally that takes on each of the trajectory values. You may optionally provide a Context that will be used as the initial condition for the simulation; otherwise the Simulator will obtain a default Context from system.

Member Function Documentation

double get_actual_realtime_rate ( ) const

Return the rate that simulated time has progressed relative to real time.

A return of 1 means the simulation just matched real time, 2 means the simulation was twice as fast as real time, 0.5 means it was running in 2X slow motion, etc.

The value returned here is calculated as follows:

         simulated_time_now - initial_simulated_time
  rate = -------------------------------------------
               realtime_now - initial_realtime

The initial times are recorded when Initialize() or ResetStatistics() is called. The returned rate is undefined if Initialize() has not yet been called.

Returns
The rate achieved since the last Initialize() or ResetStatistics() call.
See also
set_target_realtime_rate()

Here is the call graph for this function:

Here is the caller graph for this function:

const Context<T>& get_context ( ) const
inline

Returns a const reference to the internally-maintained Context holding the most recent step in the trajectory.

This is suitable for publishing or extracting information about this trajectory step.

Here is the caller graph for this function:

const IntegratorBase<T>* get_integrator ( ) const
inline

Gets a pointer to the integrator used to advance the continuous aspects of the system.

Context<T>* get_mutable_context ( )
inline

Returns a mutable pointer to the internally-maintained Context holding the most recent step in the trajectory.

This is suitable for use in updates, sampling operations, event handlers, and constraint projection. You can also modify this prior to calling Initialize() to set initial conditions.

Here is the caller graph for this function:

IntegratorBase<T>* get_mutable_integrator ( )
inline

Gets a pointer to the mutable integrator used to advance the continuous aspects of the system.

Here is the caller graph for this function:

int64_t get_num_discrete_updates ( ) const
inline

Gets the number of discrete variable updates performed since the last Initialize() call.

int64_t get_num_publishes ( ) const
inline

Gets the number of publishes made since the last Initialize() or ResetStatistics() call.

int64_t get_num_steps_taken ( ) const
inline

Gets the number of integration steps since the last Initialize() call.

int64_t get_num_unrestricted_updates ( ) const
inline

Gets the number of "unrestricted" updates performed since the last Initialize() call.

bool get_publish_every_time_step ( ) const
inline

Returns true if the simulation should invoke Publish on the System under simulation every time step.

By default, returns true.

Here is the caller graph for this function:

const System<T>& get_system ( ) const
inline

Gets a constant reference to the system.

Note
a mutable reference is not available.

Here is the caller graph for this function:

double get_target_realtime_rate ( ) const
inline

Return the real time rate target currently in effect.

The default is zero, meaning the Simulator runs as fast as possible. You can change the target with set_target_realtime_rate().

optional< T > GetCurrentWitnessTimeIsolation ( ) const

Gets the length of the interval used for witness function time isolation.

The length of the interval is computed differently, depending on context, to support multiple applications, as described below:

  • Simulations using error controlled integrators: the isolation time interval will be scaled by the product of the system's characteristic time and the accuracy stored in the Context.
  • Simulations using integrators taking fixed steps: the isolation time interval will be determined differently depending on whether the accuracy is set in the Context or not. If the accuracy is set in the Context, the nominally fixed steps for integrating continuous state will be subdivided until events have been isolated to the requisite interval length, which is scaled by the step size times the accuracy in the Context. If accuracy is not set in the Context, event isolation will not be performed.

The isolation window length will never be smaller than the integrator's working minimum tolerance (see IntegratorBase::get_working_minimum_step_size());

Returns
the isolation window if the Simulator should be isolating witness-triggered events in time, or returns empty otherwise (indicating that any witness-triggered events should trigger at the end of a time interval over which continuous state is integrated).
Exceptions
std::logic_errorif the accuracy is not set in the Context and the integrator is not operating in fixed step mode (see IntegratorBase::get_fixed_step_mode().

Here is the call graph for this function:

Here is the caller graph for this function:

void Initialize ( )

Prepares the Simulator for a simulation.

If the initial Context does not satisfy the System's constraints, an attempt is made to modify the values of the continuous state variables to satisfy the constraints. This method will throw std::logic_error if the combination of options doesn't make sense, and std::runtime_error if it is unable to find a constraint-satisfying initial condition.

Here is the call graph for this function:

Here is the caller graph for this function:

Simulator& operator= ( const Simulator< T > &  )
delete
Simulator& operator= ( Simulator< T > &&  )
delete
std::unique_ptr<Context<T> > release_context ( )
inline

Transfer ownership of this Simulator's internal Context to the caller.

The Simulator will no longer contain a Context. The caller must not attempt to advance the simulator in time after that point.

See also
reset_context()
void reset_context ( std::unique_ptr< Context< T >>  context)
inline

Replace the internally-maintained Context with a different one.

The current Context is deleted. This is useful for supplying a new set of initial conditions. You should invoke Initialize() after replacing the Context.

Parameters
contextThe new context, which may be null. If the context is null, a new context must be set before attempting to step the system forward.
U* reset_integrator ( Args &&...  args)
inline

Resets the integrator with a new one.

An example usage is:

simulator.reset_integrator<ExplicitEulerIntegrator<double>>
(sys, DT, context).

The Simulator must be reinitialized after resetting the integrator to ensure the integrator is properly initialized. You can do that explicitly with the Initialize() method or it will be done implicitly at the first time step.

Here is the caller graph for this function:

void ResetStatistics ( )

Forget accumulated statistics.

Statistics are reset to the values they have post construction or immediately after Initialize().

Here is the call graph for this function:

Here is the caller graph for this function:

void set_publish_at_initialization ( bool  publish)
inline

Sets whether the simulation should invoke Publish in Initialize().

void set_publish_every_time_step ( bool  publish)
inline

Sets whether the simulation should invoke Publish on the System under simulation during every time step.

If enabled, Publish will be invoked after discrete updates and before continuous integration. Regardless of whether publishing every time step is enabled, Publish will be invoked at Simulator initialize time, and as System<T>::CalcNextUpdateTime requests.

Here is the caller graph for this function:

void set_target_realtime_rate ( double  realtime_rate)
inline

Slow the simulation down to approximately synchronize with real time when it would otherwise run too fast.

Normally the Simulator takes steps as quickly as it can. You can request that it slow down to synchronize with real time by providing a realtime rate greater than zero here.

Warning
No guarantees can be made about how accurately the simulation can be made to track real time, even if computation is fast enough. That's because the system utilities used to implement this do not themselves provide such guarantees. So this is likely to work nicely for visualization purposes where human perception is the only concern. For any other uses you should consider whether approximate real time is adequate for your purposes.
Note
If the full-speed simulation is already slower than real time you can't speed it up with this call! Instead consider requesting less integration accuracy, using a faster integration method or fixed time step, or using a simpler model.
Parameters
realtime_rateDesired rate relative to real time. Set to 1 to track real time, 2 to run twice as fast as real time, 0.5 for half speed, etc. Zero or negative restores the rate to its default of 0, meaning the simulation will proceed as fast as possible.

Here is the caller graph for this function:

void StepTo ( const T &  boundary_time)

Advance the System's trajectory until boundary_time is reached in the context or some other termination condition occurs.

Steps the simulation to the specified time.

A variety of std::runtime_error conditions are possible here, as well as error conditions that may be thrown by the System when it is asked to perform computations. Be sure to enclose your simulation in a try-catch block and display the what() message.

We recommend that you call Initialize() prior to making the first call to StepTo(). However, if you don't it will be called for you the first time you attempt a step, possibly resulting in unexpected error conditions. See documentation for Initialize() for the error conditions it might produce.

The simulation loop is as follows:

  1. Perform necessary discrete variable updates.
  2. Publish.
  3. Integrate the smooth system (the ODE or DAE)
  4. Perform post-step stabilization for DAEs (if desired).
    Parameters
    boundary_timeThe time to advance the context to.
    Precondition
    The simulation state is valid (i.e., no discrete updates or state projections are necessary) at the present time.

Here is the call graph for this function:

Here is the caller graph for this function:


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