A class for advancing the state of hybrid dynamic systems, represented by System<T>
objects, forward in time.
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
The continuous parts of the trajectory are advanced using a numerical integrator. Different integrators have different properties; you can choose the one that is most appropriate for your application or use the default which is adequate for most systems.
This section is targeted toward users who have created a LeafSystem implementing a discrete or hybrid system. For authors of such systems, it can be useful to understand the simulation details in order to attain the desired state behavior over time. This behavior is dependent on the ordering in which discrete events and continuous updates are processed. (By "discrete events" we mean to include any of Drake's event handlers.) The basic issues and terminology are introduced in the Discrete Systems module; please look there first before proceeding.
As pictured in Discrete Systems, when a continuous-time system has discrete events, the state x can have two significant values at the event time t. These are
Thus the value of the Context, which contains both time and state, advances from {t, x⁻(t)} to {t, x⁺(t)} as a result of the update. While those Context values are user-visible, the details of stepping here require an intermediate value which we'll denote {t, x*(t)}.
Recall that Drake's state x is partitioned into continuous, discrete, and abstract partitions xc, xd, and xa, so x = { xc, xd, xa }
. Within a single step, these are updated in three stages:
Where needed, we extend the above notation to xc⁻, xa⁺, etc. to indicate the value of an individual partition at a particular stage of the stepping algorithm.
The following pseudocode uses the above notation to describe the algorithm "Step()" that the Simulator uses to incrementally advance the system trajectory (time t and state x). The Simulator's AdvanceTo() method will be defined in terms of Step below. In general, the length of a step is not known a priori and is determined by the Step() algorithm. Each step consists of zero or more unrestricted updates, followed by zero or more discrete updates, followed by (possibly zero-length) continuous time and state advancement, followed by zero or more publishes, and then a call to the monitor() function if one has been defined.
Updates, publishes, and the monitor can report errors or detect a termination condition; that is not shown in the pseudocode below. We follow this policy:
The pseudocode will clarify the effects on time and state of each of the update stages above. This algorithm is given a starting Context value {tₛ, x⁻(tₛ)}
and returns an end Context value {tₑ, x⁻(tₑ)}
, where tₑ is no later than a given tₘₐₓ.
We can use the notation and pseudocode to flesh out the AdvanceTo(), AdvancePendingEvents(), and Initialize() functions. Termination and error conditions detected by event handlers or the monitor are reported as status returns from these methods.
Initialize() can be viewed as a "0ᵗʰ step" that occurs before the first Step() call as described above. Like Step(), Initialize() first performs pending updates (in this case only initialization events can be "pending", and even those may be optionally suppressed). Time doesn't advance so there is no continuous update phase and witnesses cannot trigger. Finally, again like Step(), the initial trajectory point {t₀, x⁻(t₀)}
is provided to the handlers for any triggered publish events. That includes initialization publish events (if not suppressed), per-step publish events, and periodic or timed publish events that trigger at t₀, followed by a call to the monitor() function if one has been defined (a monitor is semantically identical to a per-step publish).
Optionally, initialization events can be suppressed. This can be useful when reusing the simulator over the same system and time span.
T | The scalar type, which must be one of the default nonsymbolic scalars. |
#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... | |
Simulator (std::unique_ptr< const System< T >> system, std::unique_ptr< Context< T >> context=nullptr) | |
Create a Simulator which additionally maintains ownership of the System. More... | |
SimulatorStatus | Initialize (const InitializeParams ¶ms={}) |
Prepares the Simulator for a simulation. More... | |
SimulatorStatus | AdvanceTo (const T &boundary_time) |
Advances the System's trajectory until boundary_time is reached in the Context or some other termination condition occurs. More... | |
SimulatorStatus | AdvancePendingEvents () |
(Advanced) Handles discrete and abstract state update events that are pending from the previous AdvanceTo() call, without advancing time. More... | |
void | set_monitor (std::function< EventStatus(const Context< T > &)> monitor) |
Provides a monitoring function that will be invoked at the end of every step. More... | |
void | clear_monitor () |
Removes the monitoring function if there is one. More... | |
const std::function< EventStatus(const Context< T > &)> & | get_monitor () const |
Obtains a reference to the monitoring function, which may be empty. 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) |
(To be deprecated) Prefer using per-step publish events instead. More... | |
void | set_publish_at_initialization (bool publish) |
(To be deprecated) Prefer using initialization or per-step publish events instead. More... | |
bool | get_publish_every_time_step () const |
Returns true if the set_publish_every_time_step() option has been enabled. 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 reference to the internally-maintained Context holding the most recent step in the trajectory. More... | |
bool | has_context () const |
Returns true if this Simulator has an internally-maintained Context. 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_steps_taken () const |
Gets the number of steps since the last Initialize() or ResetStatistics() call. More... | |
int64_t | get_num_publishes () const |
Gets the number of effective publish dispatcher calls made since the last Initialize() or ResetStatistics() call. More... | |
int64_t | get_num_discrete_updates () const |
Gets the number of effective discrete variable update dispatcher calls since the last Initialize() or ResetStatistics() call. More... | |
int64_t | get_num_unrestricted_updates () const |
Gets the number of effective unrestricted update dispatcher calls since the last Initialize() or ResetStatistics() call. More... | |
const IntegratorBase< T > & | get_integrator () const |
Gets a reference to the integrator used to advance the continuous aspects of the system. More... | |
IntegratorBase< T > & | get_mutable_integrator () |
Gets a reference to the mutable integrator used to advance the continuous state of the system. More... | |
template<class Integrator > | |
Integrator & | reset_integrator () |
Resets the integrator with a new one using factory construction. More... | |
template<class Integrator > | |
Integrator & | reset_integrator (const T max_step_size) |
Resets the integrator with a new one using factory construction and a maximum step size argument (which is required for constructing fixed-step integrators). More... | |
std::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 | |
Simulator & | operator= (const Simulator &)=delete |
Simulator (Simulator &&)=delete | |
Simulator & | operator= (Simulator &&)=delete |
Friends | |
template<typename > | |
class | internal::SimulatorPythonInternal |
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
.
Simulator | ( | std::unique_ptr< const System< T >> | system, |
std::unique_ptr< Context< T >> | context = nullptr |
||
) |
Create a Simulator which additionally maintains ownership of the System.
SimulatorStatus AdvancePendingEvents | ( | ) |
(Advanced) Handles discrete and abstract state update events that are pending from the previous AdvanceTo() call, without advancing time.
See the Simulator class description for details about how Simulator advances time and handles events. In the terminology used there, this method advances the internal Context from {t, x⁻(t)}
to {t, x⁺(t)}
.
Normally, these update events would be handled at the start of the next AdvanceTo() call, so this method is rarely needed. It can be useful at the end of a simulation or to get intermediate results when you are specifically interested in the x⁺(t)
result.
This method is equivalent to AdvanceTo(current_time)
, where current_time=simulator.get_context().get_time())
. If there are no pending events, nothing happens except possibly a final per-step publish call (if enabled) followed by a call to the monitor() function (if one has been provided).
std::exception | if any handled event reports failure. |
status | A SimulatorStatus object indicating success, termination, or an error condition as reported by event handlers or the monitor function. |
SimulatorStatus AdvanceTo | ( | const T & | boundary_time | ) |
Advances the System's trajectory until boundary_time
is reached in the Context or some other termination condition occurs.
We recommend that you call Initialize() prior to making the first call to AdvanceTo(). However, if you don't it will be called for you the first time that you attempt a step, possibly resulting in unexpected error conditions. See documentation for Initialize()
for the error conditions it might produce.
std::exception | if any handled event reports failure. Other error conditions are possible from the System and integrator in use. |
boundary_time | The maximum time to which the trajectory will be advanced by this call to AdvanceTo(). The method may return earlier if an event or the monitor function requests termination or reports an error condition. |
status | A SimulatorStatus object indicating success, termination, or an error condition as reported by event handlers or the monitor function. The time in the context will be set either to the boundary_time or the time a termination or error was first detected. |
void clear_monitor | ( | ) |
Removes the monitoring function if there is one.
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.
const Context<T>& get_context | ( | ) | const |
const IntegratorBase<T>& get_integrator | ( | ) | const |
Gets a reference to the integrator used to advance the continuous aspects of the system.
const std::function<EventStatus(const Context<T>&)>& get_monitor | ( | ) | const |
Obtains a reference to the monitoring function, which may be empty.
Context<T>& get_mutable_context | ( | ) |
Returns a mutable reference 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. Do not call this method if there is no Context.
IntegratorBase<T>& get_mutable_integrator | ( | ) |
Gets a reference to the mutable integrator used to advance the continuous state of the system.
int64_t get_num_discrete_updates | ( | ) | const |
Gets the number of effective discrete variable update dispatcher calls since the last Initialize() or ResetStatistics() call.
A dispatch is ineffective (not counted) if any of the discrete update events fails or all the discrete update events return "did nothing". A single dispatcher call may handle multiple discrete update events.
int64_t get_num_publishes | ( | ) | const |
Gets the number of effective publish dispatcher calls made since the last Initialize() or ResetStatistics() call.
A dispatch is ineffective (not counted) if any of the publish events fails or all the publish events return "did nothing". A single dispatcher call may handle multiple publish events.
int64_t get_num_steps_taken | ( | ) | const |
Gets the number of steps since the last Initialize() or ResetStatistics() call.
(We're not counting the Initialize() 0-length "step".) Note that every AdvanceTo() call can potentially take many steps.
int64_t get_num_unrestricted_updates | ( | ) | const |
Gets the number of effective unrestricted update dispatcher calls since the last Initialize() or ResetStatistics() call.
A dispatch is ineffective (not counted) if any of the unrestricted update events fails or all the unrestricted update events return "did nothing". A single dispatcher call may handle multiple unrestricted update events.
bool get_publish_every_time_step | ( | ) | const |
Returns true if the set_publish_every_time_step() option has been enabled.
By default, returns false.
const System<T>& get_system | ( | ) | const |
Gets a constant reference to the system.
double get_target_realtime_rate | ( | ) | const |
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().
std::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:
The isolation window length will never be smaller than the integrator's working minimum tolerance (see IntegratorBase::get_working_minimum_step_size());
std::exception | if the accuracy is not set in the Context and the integrator is not operating in fixed step mode (see IntegratorBase::get_fixed_step_mode(). |
bool has_context | ( | ) | const |
Returns true
if this Simulator has an internally-maintained Context.
This is always true unless reset_context()
has been called.
SimulatorStatus Initialize | ( | const InitializeParams & | params = {} | ) |
Prepares the Simulator for a simulation.
In order, the sequence of actions taken here is:
{t₀, x(t₀)}
. If initialization events are suppressed, it is the caller's responsibility to ensure the desired initial state.See the class documentation for more information. We recommend calling Initialize() explicitly prior to beginning a simulation so that error conditions will be discovered early. However, Initialize() will be called automatically by the first AdvanceTo() call if it hasn't already been called.
suppress_initialization_events
parameter set. The most common scenario for this is when reusing a Simulator object. In this case, the caller is responsible for ensuring the correctness of the initial state.std::exception | if the combination of options doesn't make sense or if any handled event reports failure. Other error conditions are possible from the System and integrator in use. |
params | (optional) a parameter structure ( |
status | A SimulatorStatus object indicating success, termination, or an error condition as reported by event handlers or the monitor function. |
std::unique_ptr<Context<T> > release_context | ( | ) |
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.
void reset_context | ( | std::unique_ptr< Context< T >> | context | ) |
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.
context | The new context, which may be null. If the context is null, a new context must be set before attempting to step the system forward. |
Integrator& reset_integrator | ( | ) |
Resets the integrator with a new one using factory construction.
Resetting the integrator resets the Simulator such that it needs to be initialized again – see Initialize() for details.
Integrator& reset_integrator | ( | const T | max_step_size | ) |
Resets the integrator with a new one using factory construction and a maximum step size argument (which is required for constructing fixed-step integrators).
void ResetStatistics | ( | ) |
Forget accumulated statistics.
Statistics are reset to the values they have post construction or immediately after Initialize()
.
void set_monitor | ( | std::function< EventStatus(const Context< T > &)> | monitor | ) |
Provides a monitoring function that will be invoked at the end of every step.
(See the Simulator class documentation for a precise definition of "step".) A monitor() function can be used to capture the trajectory, to terminate the simulation, or to detect error conditions. The monitor() function is invoked by the Simulator with a Context whose value is a point along the simulated trajectory. The monitor can be any functor and should capture any System references it needs to operate correctly.
A monitor() function behaves the same as would a per-step Publish event handler included in the top-level System or Diagram being simulated. As in the case of Publish(), the monitor is called at the end of every step taken internally by AdvanceTo(), and also at the end of Initialize() and AdvancePendingEvents(). (See the Simulator class documentation for more detail about what happens when in these methods.) The monitor receives the top-level (root) Context, from which any sub-Context can be obtained using subsystem.GetMyContextFromRoot()
, provided the necessary subsystem reference has been captured for use in the monitor.
Output time and continuous states whenever the trajectory is advanced:
Terminate early but successfully on a condition in a subsystem of the System diagram being simulated:
In the above case, the Simulator's AdvanceTo() method will return early when the subsystem reports that it has reached its goal. The returned status will indicate the termination reason, and a human-readable termination message containing the message provided by the monitor can be obtained with status.FormatMessage().
Failure due to plant center of mass falling below a threshold:
In the above case the Simulator's AdvanceTo() method will throw an std::exception containing a human-readable message including the text provided in the monitor.
void set_publish_at_initialization | ( | bool | publish | ) |
(To be deprecated) Prefer using initialization or per-step publish events instead.
Sets whether the simulation should trigger a forced-Publish at the end of Initialize(). See set_publish_every_time_step() documentation for more information.
void set_publish_every_time_step | ( | bool | publish | ) |
(To be deprecated) Prefer using per-step publish events instead.
Sets whether the simulation should trigger a forced-Publish event on the System under simulation at the end of every trajectory-advancing step. Specifically, that means the System::Publish() event dispatcher will be invoked on each subsystem of the System and passed the current Context and a forced-publish Event. If a subsystem has declared a forced-publish event handler, that will be called. Otherwise, nothing will happen.
Enabling this option does not cause a forced-publish to be triggered at initialization; if you want that you should also call set_publish_at_initialization(true)
. If you want a forced-publish at the end of every step, you will usually also want one at the end of initialization, requiring both options to be enabled.
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.
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.
realtime_rate | Desired 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. |
|
friend |