Base class for all System functionality that is dependent on the templatized scalar type T for input, state, parameters, and outputs.
T | The scalar type, which must be one of the default scalars. |
#include <drake/systems/framework/witness_function.h>
Public Types | |
using | Scalar = T |
The scalar type with which this System was instantiated. More... | |
Public Member Functions | |
~System () override | |
virtual void | Accept (SystemVisitor< T > *v) const |
Implements a visitor pattern. More... | |
void | GetWitnessFunctions (const Context< T > &context, std::vector< const WitnessFunction< T > * > *w) const |
Gets the witness functions active for the given state. More... | |
T | CalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const |
Evaluates a witness function at the given context. More... | |
virtual void | AddTriggeredWitnessFunctionToCompositeEventCollection (Event< T > *event, CompositeEventCollection< T > *events) const =0 |
Add event to events due to a witness function triggering. More... | |
DependencyTicket | discrete_state_ticket (DiscreteStateIndex index) const |
Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector). More... | |
DependencyTicket | abstract_state_ticket (AbstractStateIndex index) const |
Returns a ticket indicating dependence on a particular abstract state variable xaᵢ. More... | |
DependencyTicket | numeric_parameter_ticket (NumericParameterIndex index) const |
Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector). More... | |
DependencyTicket | abstract_parameter_ticket (AbstractParameterIndex index) const |
Returns a ticket indicating dependence on a particular abstract parameter paᵢ. More... | |
DependencyTicket | input_port_ticket (InputPortIndex index) const |
Returns a ticket indicating dependence on input port uᵢ indicated by index . More... | |
DependencyTicket | cache_entry_ticket (CacheIndex index) const |
Returns a ticket indicating dependence on the cache entry indicated by index . More... | |
Does not allow copy, move, or assignment | |
System (const System &)=delete | |
System & | operator= (const System &)=delete |
System (System &&)=delete | |
System & | operator= (System &&)=delete |
Resource allocation and initialization | |
These methods are used to allocate and initialize Context resources. | |
std::unique_ptr< Context< T > > | AllocateContext () const |
Returns a Context<T> suitable for use with this System<T>. More... | |
std::unique_ptr< CompositeEventCollection< T > > | AllocateCompositeEventCollection () const |
Allocates a CompositeEventCollection for this system. More... | |
std::unique_ptr< BasicVector< T > > | AllocateInputVector (const InputPort< T > &input_port) const |
Given an input port, allocates the vector storage. More... | |
std::unique_ptr< AbstractValue > | AllocateInputAbstract (const InputPort< T > &input_port) const |
Given an input port, allocates the abstract storage. More... | |
std::unique_ptr< SystemOutput< T > > | AllocateOutput () const |
Returns a container that can hold the values of all of this System's output ports. More... | |
virtual std::unique_ptr< ContinuousState< T > > | AllocateTimeDerivatives () const =0 |
Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext. More... | |
VectorX< T > | AllocateImplicitTimeDerivativesResidual () const |
Returns an Eigen VectorX suitable for use as the output argument to the CalcImplicitTimeDerivativesResidual() method. More... | |
virtual std::unique_ptr< DiscreteValues< T > > | AllocateDiscreteVariables () const =0 |
Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext. More... | |
std::unique_ptr< Context< T > > | CreateDefaultContext () const |
This convenience method allocates a context using AllocateContext() and sets its default values using SetDefaultContext(). More... | |
virtual void | SetDefaultParameters (const Context< T > &context, Parameters< T > *parameters) const =0 |
Assigns default values to all parameters. More... | |
virtual void | SetDefaultState (const Context< T > &context, State< T > *state) const =0 |
Assigns default values to all elements of the state. More... | |
void | SetDefaultContext (Context< T > *context) const |
Sets Context fields to their default values. More... | |
virtual void | SetRandomState (const Context< T > &context, State< T > *state, RandomGenerator *generator) const |
Assigns random values to all elements of the state. More... | |
virtual void | SetRandomParameters (const Context< T > &context, Parameters< T > *parameters, RandomGenerator *generator) const |
Assigns random values to all parameters. More... | |
void | SetRandomContext (Context< T > *context, RandomGenerator *generator) const |
Sets Context fields to random values. More... | |
void | AllocateFixedInputs (Context< T > *context) const |
For each input port, allocates a fixed input of the concrete type that this System requires, and binds it to the port, disconnecting any prior input. More... | |
bool | HasAnyDirectFeedthrough () const |
Returns true if any of the inputs to the system might be directly fed through to any of its outputs and false otherwise. More... | |
bool | HasDirectFeedthrough (int output_port) const |
Returns true if there might be direct-feedthrough from any input port to the given output_port , and false otherwise. More... | |
bool | HasDirectFeedthrough (int input_port, int output_port) const |
Returns true if there might be direct-feedthrough from the given input_port to the given output_port , and false otherwise. More... | |
virtual std::multimap< int, int > | GetDirectFeedthroughs () const=0 |
Reports all direct feedthroughs from input ports to output ports. More... | |
Publishing | |
Publishing is the primary mechanism for a System to communicate with the world outside the System abstraction during a simulation. Publishing occurs at user-specified times or events and can generate side-effect results such as terminal output, visualization, logging, plotting, and network messages. Other than computational cost, publishing has no effect on the progress of a simulation. | |
EventStatus | Publish (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const |
This method is the public entry point for dispatching all publish event handlers. More... | |
void | ForcedPublish (const Context< T > &context) const |
(Advanced) Manually triggers any PublishEvent that has trigger type kForced. More... | |
Cached evaluations | |
Given the values in a Context, a Drake System must be able to provide the results of particular computations needed for analysis and simulation of the System. These results are maintained in a mutable cache within the Context so that a result need be computed only once, the first time it is requested after a change to one of its prerequisite values. The Methods in this group that specify preconditions operate as follows: The preconditions will be checked in Debug builds but some or all might not be checked in Release builds for performance reasons. If we do check and a precondition is violated, an std::logic_error will be thrown with a helpful message. | |
const ContinuousState< T > & | EvalTimeDerivatives (const Context< T > &context) const |
Returns a reference to the cached value of the continuous state variable time derivatives, evaluating first if necessary using CalcTimeDerivatives(). More... | |
const CacheEntry & | get_time_derivatives_cache_entry () const |
(Advanced) Returns the CacheEntry used to cache time derivatives for EvalTimeDerivatives(). More... | |
const T & | EvalPotentialEnergy (const Context< T > &context) const |
Returns a reference to the cached value of the potential energy (PE), evaluating first if necessary using CalcPotentialEnergy(). More... | |
const T & | EvalKineticEnergy (const Context< T > &context) const |
Returns a reference to the cached value of the kinetic energy (KE), evaluating first if necessary using CalcKineticEnergy(). More... | |
const T & | EvalConservativePower (const Context< T > &context) const |
Returns a reference to the cached value of the conservative power (Pc), evaluating first if necessary using CalcConservativePower(). More... | |
const T & | EvalNonConservativePower (const Context< T > &context) const |
Returns a reference to the cached value of the non-conservative power (Pnc), evaluating first if necessary using CalcNonConservativePower(). More... | |
template<template< typename > class Vec = BasicVector> | |
const Vec< T > * | EvalVectorInput (const Context< T > &context, int port_index) const |
Returns the value of the vector-valued input port with the given port_index as a BasicVector or a specific subclass Vec derived from BasicVector. More... | |
Constraint-related functions | |
SystemConstraintIndex | AddExternalConstraint (ExternalSystemConstraint constraint) |
Adds an "external" constraint to this System. More... | |
Calculations | |
A Drake System defines a set of common computations that are understood by the framework. Most of these are embodied in a This group also includes additional System-specific operations that depend on both Context and additional input arguments. | |
void | CalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const |
Calculates the time derivatives ẋ꜀ of the continuous state x꜀ into a given output argument. More... | |
void | CalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const |
Evaluates the implicit form of the System equations and returns the residual. More... | |
EventStatus | CalcDiscreteVariableUpdate (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const |
This method is the public entry point for dispatching all discrete variable update event handlers. More... | |
void | ApplyDiscreteVariableUpdate (const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state, Context< T > *context) const |
Given the discrete_state results of a previous call to CalcDiscreteVariableUpdate() that dispatched the given collection of events, modifies the context to reflect the updated discrete_state . More... | |
void | CalcForcedDiscreteVariableUpdate (const Context< T > &context, DiscreteValues< T > *discrete_state) const |
(Advanced) Manually triggers any DiscreteUpdateEvent that has trigger type kForced. More... | |
EventStatus | CalcUnrestrictedUpdate (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const |
This method is the public entry point for dispatching all unrestricted update event handlers. More... | |
void | ApplyUnrestrictedUpdate (const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state, Context< T > *context) const |
Given the state results of a previous call to CalcUnrestrictedUpdate() that dispatched the given collection of events, modifies the context to reflect the updated state . More... | |
void | CalcForcedUnrestrictedUpdate (const Context< T > &context, State< T > *state) const |
(Advanced) Manually triggers any UnrestrictedUpdateEvent that has trigger type kForced. More... | |
T | CalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events) const |
This method is called by a Simulator during its calculation of the size of the next continuous step to attempt. More... | |
void | GetPeriodicEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
Returns all periodic events in this System. More... | |
void | GetPerStepEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in AdvanceTo() at the point before Simulator integrates continuous state. More... | |
void | GetInitializationEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
This method is called by Simulator::Initialize() to gather all update and publish events that need to be handled at initialization before the simulator starts integration. More... | |
void | ExecuteInitializationEvents (Context< T > *context) const |
This method triggers all of the initialization events returned by GetInitializationEvents(). More... | |
void | ExecuteForcedEvents (Context< T > *context, bool publish=true) const |
This method triggers all of the forced events registered with this System (which might be a Diagram). More... | |
std::optional< PeriodicEventData > | GetUniquePeriodicDiscreteUpdateAttribute () const |
Determines whether there exists a unique periodic timing (offset and period) that triggers one or more discrete update events (and, if so, returns that unique periodic timing). More... | |
const DiscreteValues< T > & | EvalUniquePeriodicDiscreteUpdate (const Context< T > &context) const |
If this System contains a unique periodic timing for discrete update events, this function executes the handlers for those periodic events to determine what their effect would be. More... | |
bool | IsDifferenceEquationSystem (double *time_period=nullptr) const |
Returns true iff the state dynamics of this system are governed exclusively by a difference equation on a single discrete state group and with a unique periodic update (having zero offset). More... | |
bool | IsDifferentialEquationSystem () const |
Returns true iff the state dynamics of this system are governed exclusively by a differential equation. More... | |
std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparator > | MapPeriodicEventsByTiming (const Context< T > *context=nullptr) const |
Maps all periodic triggered events for a System, organized by timing. More... | |
void | CalcOutput (const Context< T > &context, SystemOutput< T > *outputs) const |
Utility method that computes for every output port i the value y(i) that should result from the current contents of the given Context. More... | |
T | CalcPotentialEnergy (const Context< T > &context) const |
Calculates and returns the potential energy represented by the current configuration provided in context . More... | |
T | CalcKineticEnergy (const Context< T > &context) const |
Calculates and returns the kinetic energy represented by the current configuration and velocity provided in context . More... | |
T | CalcConservativePower (const Context< T > &context) const |
Calculates and returns the conservative power represented by the current contents of the given context . More... | |
T | CalcNonConservativePower (const Context< T > &context) const |
Calculates and returns the non-conservative power represented by the current contents of the given context . More... | |
void | MapVelocityToQDot (const Context< T > &context, const VectorBase< T > &generalized_velocity, VectorBase< T > *qdot) const |
Transforms a given generalized velocity v to the time derivative qdot of the generalized configuration q taken from the supplied Context. More... | |
void | MapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const |
Transforms the given generalized velocity to the time derivative of generalized configuration. More... | |
void | MapQDotToVelocity (const Context< T > &context, const VectorBase< T > &qdot, VectorBase< T > *generalized_velocity) const |
Transforms the time derivative qdot of the generalized configuration q to generalized velocities v . More... | |
void | MapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const |
Transforms the given time derivative qdot of generalized configuration q to generalized velocity v . More... | |
Subcontext access | |
Methods in this section locate the Context belonging to a particular subsystem, from within the Context for a containing System (typically a Diagram). There are two common circumstances where this is needed:
The second case is particularly useful in monitor functions for the Drake Simulator. | |
const Context< T > & | GetSubsystemContext (const System< T > &subsystem, const Context< T > &context) const |
Returns a const reference to the subcontext that corresponds to the contained System subsystem . More... | |
Context< T > & | GetMutableSubsystemContext (const System< T > &subsystem, Context< T > *context) const |
Returns a mutable reference to the subcontext that corresponds to the contained System subsystem . More... | |
const Context< T > & | GetMyContextFromRoot (const Context< T > &root_context) const |
Returns the const Context for this subsystem, given a root context. More... | |
Context< T > & | GetMyMutableContextFromRoot (Context< T > *root_context) const |
Returns the mutable subsystem context for this system, given a root context. More... | |
Utility methods | |
const InputPort< T > & | get_input_port (int port_index, bool warn_deprecated=true) const |
Returns the typed input port at index port_index . More... | |
const InputPort< T > & | get_input_port () const |
Convenience method for the case of exactly one input port. More... | |
const InputPort< T > * | get_input_port_selection (std::variant< InputPortSelection, InputPortIndex > port_index) const |
Returns the typed input port specified by the InputPortSelection or by the InputPortIndex. More... | |
const InputPort< T > & | GetInputPort (const std::string &port_name) const |
Returns the typed input port with the unique name port_name . More... | |
bool | HasInputPort (const std::string &port_name) const |
Returns true iff the system has an InputPort of the given port_name . More... | |
const OutputPort< T > & | get_output_port (int port_index, bool warn_deprecated=true) const |
Returns the typed output port at index port_index . More... | |
const OutputPort< T > & | get_output_port () const |
Convenience method for the case of exactly one output port. More... | |
const OutputPort< T > * | get_output_port_selection (std::variant< OutputPortSelection, OutputPortIndex > port_index) const |
Returns the typed output port specified by the OutputPortSelection or by the OutputPortIndex. More... | |
const OutputPort< T > & | GetOutputPort (const std::string &port_name) const |
Returns the typed output port with the unique name port_name . More... | |
bool | HasOutputPort (const std::string &port_name) const |
Returns true iff the system has an OutputPort of the given port_name . More... | |
int | num_constraints () const |
Returns the number of constraints specified for the system. More... | |
const SystemConstraint< T > & | get_constraint (SystemConstraintIndex constraint_index) const |
Returns the constraint at index constraint_index . More... | |
boolean< T > | CheckSystemConstraintsSatisfied (const Context< T > &context, double tol) const |
Returns true if context satisfies all of the registered SystemConstraints with tolerance tol . More... | |
VectorX< T > | CopyContinuousStateVector (const Context< T > &context) const |
Returns a copy of the continuous state vector x꜀ into an Eigen vector. More... | |
std::string | GetMemoryObjectName () const |
Returns a name for this System based on a stringification of its type name and memory address. More... | |
int | num_input_ports () const |
Returns the number of input ports currently allocated in this System. More... | |
int | num_output_ports () const |
Returns the number of output ports currently allocated in this System. More... | |
Scalar type conversion utilities | |
void | FixInputPortsFrom (const System< double > &other_system, const Context< double > &other_context, Context< T > *target_context) const |
Fixes all of the input ports in target_context to their current values in other_context , as evaluated by other_system . More... | |
const SystemScalarConverter & | get_system_scalar_converter () const |
(Advanced) Returns the SystemScalarConverter for this object. More... | |
Graphviz methods | |
std::string | GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
Returns a Graphviz string describing this System. More... | |
Public Member Functions inherited from SystemBase | |
~SystemBase () override | |
void | set_name (const std::string &name) |
Sets the name of the system. More... | |
const std::string & | get_name () const |
Returns the name last supplied to set_name(), if any. More... | |
std::string | GetMemoryObjectName () const |
Returns a name for this System based on a stringification of its type name and memory address. More... | |
const std::string & | GetSystemName () const final |
Returns a human-readable name for this system, for use in messages and logging. More... | |
std::string | GetSystemPathname () const final |
Generates and returns a human-readable full path name of this subsystem, for use in messages and logging. More... | |
std::string | GetSystemType () const final |
Returns the most-derived type of this concrete System object as a human-readable string suitable for use in error messages. More... | |
std::unique_ptr< ContextBase > | AllocateContext () const |
Returns a Context suitable for use with this System. More... | |
int | num_input_ports () const |
Returns the number of input ports currently allocated in this System. More... | |
int | num_output_ports () const |
Returns the number of output ports currently allocated in this System. More... | |
const InputPortBase & | get_input_port_base (InputPortIndex port_index) const |
Returns a reference to an InputPort given its port_index . More... | |
const OutputPortBase & | get_output_port_base (OutputPortIndex port_index) const |
Returns a reference to an OutputPort given its port_index . More... | |
int | num_total_inputs () const |
Returns the total dimension of all of the vector-valued input ports (as if they were muxed). More... | |
int | num_total_outputs () const |
Returns the total dimension of all of the vector-valued output ports (as if they were muxed). More... | |
virtual std::multimap< int, int > | GetDirectFeedthroughs () const =0 |
Reports all direct feedthroughs from input ports to output ports. More... | |
int | num_cache_entries () const |
Returns the number nc of cache entries currently allocated in this System. More... | |
const CacheEntry & | get_cache_entry (CacheIndex index) const |
Returns a reference to a CacheEntry given its index . More... | |
CacheEntry & | get_mutable_cache_entry (CacheIndex index) |
(Advanced) Returns a mutable reference to a CacheEntry given its index . More... | |
int | num_continuous_states () const |
Returns the number of declared continuous state variables. More... | |
int | num_discrete_state_groups () const |
Returns the number of declared discrete state groups (each group is a vector-valued discrete state variable). More... | |
int | num_abstract_states () const |
Returns the number of declared abstract state variables. More... | |
int | num_numeric_parameter_groups () const |
Returns the number of declared numeric parameters (each of these is a vector-valued parameter). More... | |
int | num_abstract_parameters () const |
Returns the number of declared abstract parameters. More... | |
int | implicit_time_derivatives_residual_size () const |
Returns the size of the implicit time derivatives residual vector. More... | |
void | ValidateContext (const ContextBase &context) const final |
Checks whether the given context was created for this system. More... | |
void | ValidateContext (const ContextBase *context) const |
Checks whether the given context was created for this system. More... | |
template<class Clazz > | |
void | ValidateCreatedForThisSystem (const Clazz &object) const |
Checks whether the given object was created for this system. More... | |
SystemBase (const SystemBase &)=delete | |
SystemBase & | operator= (const SystemBase &)=delete |
SystemBase (SystemBase &&)=delete | |
SystemBase & | operator= (SystemBase &&)=delete |
std::string | GetGraphvizString (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
Returns a Graphviz string describing this System. More... | |
GraphvizFragment | GetGraphvizFragment (std::optional< int > max_depth={}, const std::map< std::string, std::string > &options={}) const |
(Advanced) Like GetGraphvizString() but does not wrap the string in a digraph { … } . More... | |
const AbstractValue * | EvalAbstractInput (const ContextBase &context, int port_index) const |
Returns the value of the input port with the given port_index as an AbstractValue, which is permitted for ports of any type. More... | |
template<typename V > | |
const V * | EvalInputValue (const ContextBase &context, int port_index) const |
Returns the value of an abstract-valued input port with the given port_index as a value of known type V . More... | |
DependencyTicket | discrete_state_ticket (DiscreteStateIndex index) const |
Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector). More... | |
DependencyTicket | abstract_state_ticket (AbstractStateIndex index) const |
Returns a ticket indicating dependence on a particular abstract state variable xaᵢ. More... | |
DependencyTicket | numeric_parameter_ticket (NumericParameterIndex index) const |
Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector). More... | |
DependencyTicket | abstract_parameter_ticket (AbstractParameterIndex index) const |
Returns a ticket indicating dependence on a particular abstract parameter paᵢ. More... | |
DependencyTicket | input_port_ticket (InputPortIndex index) const |
Returns a ticket indicating dependence on input port uᵢ indicated by index . More... | |
DependencyTicket | cache_entry_ticket (CacheIndex index) const |
Returns a ticket indicating dependence on the cache entry indicated by index . More... | |
DependencyTicket | output_port_ticket (OutputPortIndex index) const |
(Internal use only) Returns a ticket indicating dependence on the output port indicated by index . More... | |
Static Public Member Functions | |
static DependencyTicket | nothing_ticket () |
Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More... | |
static DependencyTicket | time_ticket () |
Returns a ticket indicating dependence on time. More... | |
static DependencyTicket | accuracy_ticket () |
Returns a ticket indicating dependence on the accuracy setting in the Context. More... | |
static DependencyTicket | q_ticket () |
Returns a ticket indicating that a computation depends on configuration state variables q. More... | |
static DependencyTicket | v_ticket () |
Returns a ticket indicating dependence on velocity state variables v. More... | |
static DependencyTicket | z_ticket () |
Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More... | |
static DependencyTicket | xc_ticket () |
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More... | |
static DependencyTicket | xd_ticket () |
Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More... | |
static DependencyTicket | xa_ticket () |
Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More... | |
static DependencyTicket | all_state_ticket () |
Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More... | |
static DependencyTicket | pn_ticket () |
Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More... | |
static DependencyTicket | pa_ticket () |
Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More... | |
static DependencyTicket | all_parameters_ticket () |
Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More... | |
static DependencyTicket | all_input_ports_ticket () |
Returns a ticket indicating dependence on all input ports u of this system. More... | |
static DependencyTicket | all_sources_ticket () |
Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More... | |
static DependencyTicket | configuration_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More... | |
static DependencyTicket | kinematics_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More... | |
static DependencyTicket | xcdot_ticket () |
Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More... | |
static DependencyTicket | pe_ticket () |
Returns a ticket for the cache entry that holds the potential energy calculation. More... | |
static DependencyTicket | ke_ticket () |
Returns a ticket for the cache entry that holds the kinetic energy calculation. More... | |
static DependencyTicket | pc_ticket () |
Returns a ticket for the cache entry that holds the conservative power calculation. More... | |
static DependencyTicket | pnc_ticket () |
Returns a ticket for the cache entry that holds the non-conservative power calculation. More... | |
Static Public Member Functions inherited from SystemBase | |
static DependencyTicket | nothing_ticket () |
Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More... | |
static DependencyTicket | time_ticket () |
Returns a ticket indicating dependence on time. More... | |
static DependencyTicket | accuracy_ticket () |
Returns a ticket indicating dependence on the accuracy setting in the Context. More... | |
static DependencyTicket | q_ticket () |
Returns a ticket indicating that a computation depends on configuration state variables q. More... | |
static DependencyTicket | v_ticket () |
Returns a ticket indicating dependence on velocity state variables v. More... | |
static DependencyTicket | z_ticket () |
Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More... | |
static DependencyTicket | xc_ticket () |
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More... | |
static DependencyTicket | xd_ticket () |
Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More... | |
static DependencyTicket | xa_ticket () |
Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More... | |
static DependencyTicket | all_state_ticket () |
Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More... | |
static DependencyTicket | pn_ticket () |
Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More... | |
static DependencyTicket | pa_ticket () |
Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More... | |
static DependencyTicket | all_parameters_ticket () |
Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More... | |
static DependencyTicket | all_input_ports_ticket () |
Returns a ticket indicating dependence on all input ports u of this system. More... | |
static DependencyTicket | all_sources_except_input_ports_ticket () |
Returns a ticket indicating dependence on every possible independent source value except input ports. More... | |
static DependencyTicket | all_sources_ticket () |
Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More... | |
static DependencyTicket | configuration_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More... | |
static DependencyTicket | kinematics_ticket () |
Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More... | |
static DependencyTicket | xcdot_ticket () |
Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More... | |
static DependencyTicket | pe_ticket () |
Returns a ticket for the cache entry that holds the potential energy calculation. More... | |
static DependencyTicket | ke_ticket () |
Returns a ticket for the cache entry that holds the kinetic energy calculation. More... | |
static DependencyTicket | pc_ticket () |
Returns a ticket for the cache entry that holds the conservative power calculation. More... | |
static DependencyTicket | pnc_ticket () |
Returns a ticket for the cache entry that holds the non-conservative power calculation. More... | |
static DependencyTicket | xd_unique_periodic_update_ticket () |
(Internal use only) Returns a ticket for the cache entry that holds the unique periodic discrete update computation. More... | |
Protected Member Functions | |
virtual T | DoCalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const =0 |
Derived classes will implement this method to evaluate a witness function at the given context. More... | |
virtual void | DoGetWitnessFunctions (const Context< T > &, std::vector< const WitnessFunction< T > * > *) const |
Derived classes can override this method to provide witness functions active for the given state. More... | |
SystemConstraintIndex | AddConstraint (std::unique_ptr< SystemConstraint< T >> constraint) |
Adds an already-created constraint to the list of constraints for this System. More... | |
bool | forced_publish_events_exist () const |
bool | forced_discrete_update_events_exist () const |
bool | forced_unrestricted_update_events_exist () const |
EventCollection< PublishEvent< T > > & | get_mutable_forced_publish_events () |
EventCollection< DiscreteUpdateEvent< T > > & | get_mutable_forced_discrete_update_events () |
EventCollection< UnrestrictedUpdateEvent< T > > & | get_mutable_forced_unrestricted_update_events () |
const EventCollection< DiscreteUpdateEvent< T > > & | get_forced_discrete_update_events () const |
const EventCollection< UnrestrictedUpdateEvent< T > > & | get_forced_unrestricted_update_events () const |
void | set_forced_publish_events (std::unique_ptr< EventCollection< PublishEvent< T >>> forced) |
void | set_forced_discrete_update_events (std::unique_ptr< EventCollection< DiscreteUpdateEvent< T >>> forced) |
void | set_forced_unrestricted_update_events (std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T >>> forced) |
SystemScalarConverter & | get_mutable_system_scalar_converter () |
Returns the SystemScalarConverter for this system. More... | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the most generic form of the calculation function. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, const ValueType &model_value, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying a model value of concrete type ValueType and a calculator function that is a class member function (method) with signature: More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More... | |
(Internal use only) Event handler dispatch mechanism | |
The pure virtuals declared here are intended to be implemented only by Drake's LeafSystem and Diagram (plus a few unit tests) and those implementations must be For a LeafSystem, these functions need to call each event's handler callback, For a LeafSystem, the pseudo code of the complete default publish event handler dispatching is roughly: leaf_sys.Publish(context, event_collection) -> leaf_sys.DispatchPublishHandler(context, event_collection) for (event : event_collection_events): if (event.has_handler) event.handler(context) Discrete update events and unrestricted update events are dispatched similarly for a LeafSystem. EventStatus is propagated upwards from the individual event handlers with the first worst retained. For a Diagram, these functions must iterate through all subsystems, extract their corresponding subcontext and subevent collections from All of these functions are only called from their corresponding public non-virtual event dispatchers, where | |
virtual EventStatus | DispatchPublishHandler (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const =0 |
(Internal use only) This function dispatches all publish events to the appropriate handlers. More... | |
virtual EventStatus | DispatchDiscreteVariableUpdateHandler (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const =0 |
(Internal use only) This function dispatches all discrete update events to the appropriate handlers. More... | |
virtual void | DoApplyDiscreteVariableUpdate (const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state, Context< T > *context) const =0 |
(Internal use only) Updates the given context with the results returned from a previous call to DispatchDiscreteVariableUpdateHandler() that handled the given events . More... | |
virtual EventStatus | DispatchUnrestrictedUpdateHandler (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const =0 |
(Internal use only) This function dispatches all unrestricted update events to the appropriate handlers. More... | |
virtual void | DoApplyUnrestrictedUpdate (const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state, Context< T > *context) const =0 |
(Internal use only) Updates the given context with the results returned from a previous call to DispatchUnrestrictedUpdateHandler() that handled the given events . More... | |
System construction | |
Authors of derived Systems can use these methods in the constructor for those Systems. | |
System (SystemScalarConverter converter) | |
Constructs an empty System base class object and allocates base class resources, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter . More... | |
InputPort< T > & | DeclareInputPort (std::variant< std::string, UseDefaultName > name, PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt) |
Adds a port with the specified type and size to the input topology. More... | |
Virtual methods for calculations | |
These virtuals allow concrete systems to implement the calculations defined by the Most have default implementations that are usable for simple systems, but you are likely to need to override some or all of these in your concrete system to produce meaningful calculations. These methods are invoked by the corresponding method in the public interface that has the same name with | |
virtual void | DoCalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const |
Override this if you have any continuous state variables x꜀ in your concrete System to calculate their time derivatives. More... | |
virtual void | DoCalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const |
Override this if you have an efficient way to evaluate the implicit time derivatives residual for this System. More... | |
virtual void | DoCalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events, T *time) const |
Computes the next time at which this System must perform a discrete action. More... | |
virtual std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparator > | DoMapPeriodicEventsByTiming (const Context< T > &context) const =0 |
Implement this method to return all periodic triggered events organized by timing. More... | |
virtual void | DoGetPeriodicEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
Implement this method to return any periodic events. More... | |
virtual void | DoGetPerStepEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
Implement this method to return any events to be handled before the simulator integrates the system's continuous state at each time step. More... | |
virtual void | DoGetInitializationEvents (const Context< T > &context, CompositeEventCollection< T > *events) const |
Implement this method to return any events to be handled at the simulator's initialization step. More... | |
virtual T | DoCalcPotentialEnergy (const Context< T > &context) const |
Override this method for physical systems to calculate the potential energy PE currently stored in the configuration provided in the given Context. More... | |
virtual T | DoCalcKineticEnergy (const Context< T > &context) const |
Override this method for physical systems to calculate the kinetic energy KE currently present in the motion provided in the given Context. More... | |
virtual T | DoCalcConservativePower (const Context< T > &context) const |
Override this method to return the rate Pc at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context. More... | |
virtual T | DoCalcNonConservativePower (const Context< T > &context) const |
Override this method to return the rate Pnc at which work W is done on the system by non-conservative forces. More... | |
virtual void | DoMapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const |
Provides the substantive implementation of MapQDotToVelocity(). More... | |
virtual void | DoMapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const |
Provides the substantive implementation of MapVelocityToQDot(). More... | |
Utility methods (protected) | |
Eigen::VectorBlock< VectorX< T > > | GetMutableOutputVector (SystemOutput< T > *output, int port_index) const |
Returns a mutable Eigen expression for a vector valued output port with index port_index in this system. More... | |
Protected Member Functions inherited from SystemBase | |
SystemBase ()=default | |
(Internal use only). More... | |
void | AddInputPort (std::unique_ptr< InputPortBase > port) |
(Internal use only) Adds an already-constructed input port to this System. More... | |
void | AddOutputPort (std::unique_ptr< OutputPortBase > port) |
(Internal use only) Adds an already-constructed output port to this System. More... | |
std::string | NextInputPortName (std::variant< std::string, UseDefaultName > given_name) const |
(Internal use only) Returns a name for the next input port, using the given name if it isn't kUseDefaultName, otherwise making up a name like "u3" from the next available input port index. More... | |
std::string | NextOutputPortName (std::variant< std::string, UseDefaultName > given_name) const |
(Internal use only) Returns a name for the next output port, using the given name if it isn't kUseDefaultName, otherwise making up a name like "y3" from the next available output port index. More... | |
void | AddDiscreteStateGroup (DiscreteStateIndex index) |
(Internal use only) Assigns a ticket to a new discrete variable group with the given index . More... | |
void | AddAbstractState (AbstractStateIndex index) |
(Internal use only) Assigns a ticket to a new abstract state variable with the given index . More... | |
void | AddNumericParameter (NumericParameterIndex index) |
(Internal use only) Assigns a ticket to a new numeric parameter with the given index . More... | |
void | AddAbstractParameter (AbstractParameterIndex index) |
(Internal use only) Assigns a ticket to a new abstract parameter with the given index . More... | |
CacheEntry & | DeclareCacheEntryWithKnownTicket (DependencyTicket known_ticket, std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
(Internal use only) This is for cache entries associated with pre-defined tickets, for example the cache entry for time derivatives. More... | |
const internal::SystemParentServiceInterface * | get_parent_service () const |
Returns a pointer to the service interface of the immediately enclosing Diagram if one has been set, otherwise nullptr. More... | |
DependencyTicket | assign_next_dependency_ticket () |
(Internal use only) Assigns the next unused dependency ticket number, unique only within a particular system. More... | |
const AbstractValue * | EvalAbstractInputImpl (const char *func, const ContextBase &context, InputPortIndex port_index) const |
(Internal use only) Shared code for updating an input port and returning a pointer to its abstract value, or nullptr if the port is not connected. More... | |
void | ThrowNegativePortIndex (const char *func, int port_index) const |
Throws std::exception to report a negative port_index that was passed to API method func . More... | |
void | ThrowInputPortIndexOutOfRange (const char *func, InputPortIndex port_index) const |
Throws std::exception to report bad input port_index that was passed to API method func . More... | |
void | ThrowOutputPortIndexOutOfRange (const char *func, OutputPortIndex port_index) const |
Throws std::exception to report bad output port_index that was passed to API method func . More... | |
void | ThrowNotAVectorInputPort (const char *func, InputPortIndex port_index) const |
Throws std::exception because someone misused API method func , that is only allowed for declared-vector input ports, on an abstract port whose index is given here. More... | |
void | ThrowInputPortHasWrongType (const char *func, InputPortIndex port_index, const std::string &expected_type, const std::string &actual_type) const |
Throws std::exception because someone called API method func claiming the input port had some value type that was wrong. More... | |
void | ThrowCantEvaluateInputPort (const char *func, InputPortIndex port_index) const |
Throws std::exception because someone called API method func , that requires this input port to be evaluatable, but the port was neither fixed nor connected. More... | |
const InputPortBase & | GetInputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const |
(Internal use only) Returns the InputPortBase at index port_index , throwing std::exception we don't like the port index. More... | |
const OutputPortBase & | GetOutputPortBaseOrThrow (const char *func, int port_index, bool warn_deprecated) const |
(Internal use only) Returns the OutputPortBase at index port_index , throwing std::exception if we don't like the port index. More... | |
void | ThrowValidateContextMismatch (const ContextBase &) const |
(Internal use only) Throws std::exception with a message that the sanity check(s) given by ValidateContext have failed. More... | |
virtual std::string | GetUnsupportedScalarConversionMessage (const std::type_info &source_type, const std::type_info &destination_type) const |
(Internal use only) Returns the message to use for a std::exception in the case of unsupported scalar type conversions. More... | |
void | InitializeContextBase (ContextBase *context) const |
This method must be invoked from within derived class DoAllocateContext() implementations right after the concrete Context object has been allocated. More... | |
virtual std::unique_ptr< ContextBase > | DoAllocateContext () const =0 |
Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method. More... | |
const ContextSizes & | get_context_sizes () const |
Obtains access to the declared Context partition sizes as accumulated during LeafSystem or Diagram construction . More... | |
ContextSizes & | get_mutable_context_sizes () |
Obtains mutable access to the Context sizes struct. More... | |
void | set_implicit_time_derivatives_residual_size (int n) |
Allows a LeafSystem to override the default size for the implicit time derivatives residual and a Diagram to sum up the total size. More... | |
internal::SystemId | get_system_id () const |
(Internal) Gets the id used to tag context data as being created by this system. More... | |
virtual GraphvizFragment | DoGetGraphvizFragment (const GraphvizFragmentParams ¶ms) const |
The NVI implementation of GetGraphvizFragment() for subclasses to override if desired. More... | |
CacheEntry & | DeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a new CacheEntry in this System using the most generic form of the calculation function. More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, const ValueType &model_value, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying a model value of concrete type ValueType and a calculator function that is a class member function (method) with signature: More... | |
template<class MySystem , class MyContext , typename ValueType > | |
CacheEntry & | DeclareCacheEntry (std::string description, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()}) |
Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More... | |
Static Protected Member Functions | |
static void | FindUniquePeriodicDiscreteUpdatesOrThrow (const char *api_name, const System< T > &system, const Context< T > &context, std::optional< PeriodicEventData > *timing, EventCollection< DiscreteUpdateEvent< T >> *events) |
(Internal use only) Static interface to DoFindUniquePeriodicDiscreteUpdatesOrThrow() to allow a Diagram to invoke that private method on its subsystems. More... | |
Static Protected Member Functions inherited from SystemBase | |
static void | set_parent_service (SystemBase *child, const internal::SystemParentServiceInterface *parent_service) |
(Internal use only) Declares that parent_service is the service interface of the Diagram that owns this subsystem. More... | |
static void | ThrowInputPortHasWrongType (const char *func, const std::string &system_pathname, InputPortIndex, const std::string &port_name, const std::string &expected_type, const std::string &actual_type) |
Throws std::exception because someone called API method func claiming the input port had some value type that was wrong. More... | |
static const ContextSizes & | get_context_sizes (const SystemBase &system) |
Allows Diagram to access protected get_context_sizes() recursively on its subsystems. More... | |
Friends | |
template<typename > | |
class | System |
Cloning | |
std::unique_ptr< System< T > > | Clone () const |
Creates a deep copy of this system. More... | |
template<template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< T > > | Clone (const S< T > &from) |
Creates a deep copy of this system. More... | |
Automatic differentiation | |
From a System templatized by | |
std::unique_ptr< System< AutoDiffXd > > | ToAutoDiffXd () const |
Creates a deep copy of this System, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More... | |
std::unique_ptr< System< AutoDiffXd > > | ToAutoDiffXdMaybe () const |
Creates a deep copy of this system exactly like ToAutoDiffXd(), but returns nullptr if this System does not support autodiff, instead of throwing an exception. More... | |
template<template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< AutoDiffXd > > | ToAutoDiffXd (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives. More... | |
Symbolics | |
From a System templatized by | |
std::unique_ptr< System< symbolic::Expression > > | ToSymbolic () const |
Creates a deep copy of this System, transmogrified to use the symbolic scalar type. More... | |
std::unique_ptr< System< symbolic::Expression > > | ToSymbolicMaybe () const |
Creates a deep copy of this system exactly like ToSymbolic(), but returns nullptr if this System does not support symbolic, instead of throwing an exception. More... | |
template<template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< symbolic::Expression > > | ToSymbolic (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the symbolic scalar type. More... | |
Scalar type conversion by template parameter | |
These routines allow arbitrary scalar type conversion to be attempted. Not all conversions will be supported, for various reasons.
| |
template<typename U > | |
std::unique_ptr< System< U > > | ToScalarType () const |
Creates a deep copy of this System, transmogrified to use the scalar type selected by a template parameter. More... | |
template<typename U > | |
std::unique_ptr< System< U > > | ToScalarTypeMaybe () const |
Creates a deep copy of this system exactly like ToScalarType(), but returns nullptr if this System does not support the destination type, instead of throwing an exception. More... | |
template<typename U , template< typename > class S = ::drake::systems::System> | |
static std::unique_ptr< S< U > > | ToScalarType (const S< T > &from) |
Creates a deep copy of from , transmogrified to use the scalar type selected by a template parameter. More... | |
using Scalar = T |
The scalar type with which this System was instantiated.
|
override |
|
explicitprotected |
Constructs an empty System base class object and allocates base class resources, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter
.
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
DependencyTicket abstract_parameter_ticket |
Returns a ticket indicating dependence on a particular abstract parameter paᵢ.
DependencyTicket abstract_state_ticket |
Returns a ticket indicating dependence on a particular abstract state variable xaᵢ.
|
virtual |
Implements a visitor pattern.
Reimplemented in Diagram< T >, and Diagram< double >.
|
static |
Returns a ticket indicating dependence on the accuracy setting in the Context.
This is the same ticket for all systems and refers to the same accuracy value.
|
protected |
Adds an already-created constraint to the list of constraints for this System.
Ownership of the SystemConstraint is transferred to this system.
SystemConstraintIndex AddExternalConstraint | ( | ExternalSystemConstraint | constraint | ) |
Adds an "external" constraint to this System.
This method is intended for use by applications that are examining this System to add additional constraints based on their particular situation (e.g., that a velocity state element has an upper bound); it is not intended for declaring intrinsic constraints that some particular System subclass might always impose on itself (e.g., that a mass parameter is non-negative). To that end, this method should not be called by subclasses of this
during their constructor.
The constraint
will automatically persist across system scalar conversion.
|
pure virtual |
Add event
to events
due to a witness function triggering.
events
should be allocated with this system's AllocateCompositeEventCollection. Neither event
nor events
can be nullptr. Additionally, event
must contain event data (event->get_event_data() must not be nullptr) and the type of that data must be WitnessTriggeredEventData.
Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, and LeafSystem< AutoDiffXd >.
|
static |
Returns a ticket indicating dependence on all input ports u of this system.
|
static |
Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa.
|
static |
Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries).
This is the default dependency for computations that have not specified anything more refined. It is equivalent to the set {all_sources_except_input_ports_ticket(), all_input_ports_ticket()}
.
|
static |
Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa.
This does not imply dependence on time, accuracy, parameters, or inputs; those must be specified separately. If you mean to express dependence on all possible value sources, use all_sources_ticket() instead.
std::unique_ptr<CompositeEventCollection<T> > AllocateCompositeEventCollection | ( | ) | const |
Allocates a CompositeEventCollection for this system.
The allocated instance is used for populating collections of triggered events; for example, Simulator passes this object to System::CalcNextUpdateTime() to allow the system to identify and handle upcoming events.
std::unique_ptr<Context<T> > AllocateContext | ( | ) | const |
Returns a Context<T> suitable for use with this System<T>.
|
pure virtual |
Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext.
The simulator will provide this state as the output argument to Update.
Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, and LeafSystem< AutoDiffXd >.
void AllocateFixedInputs | ( | Context< T > * | context | ) | const |
For each input port, allocates a fixed input of the concrete type that this System requires, and binds it to the port, disconnecting any prior input.
Does not assign any values to the fixed inputs.
VectorX<T> AllocateImplicitTimeDerivativesResidual | ( | ) | const |
Returns an Eigen VectorX suitable for use as the output argument to the CalcImplicitTimeDerivativesResidual() method.
The returned VectorX will have size implicit_time_derivatives_residual_size() with the elements uninitialized. This is just a convenience method – you are free to use any properly-sized mutable Eigen object as the residual vector.
std::unique_ptr<AbstractValue> AllocateInputAbstract | ( | const InputPort< T > & | input_port | ) | const |
Given an input port, allocates the abstract storage.
The input_port
must match a port declared via DeclareInputPort.
std::unique_ptr<BasicVector<T> > AllocateInputVector | ( | const InputPort< T > & | input_port | ) | const |
Given an input port, allocates the vector storage.
The input_port
must match a port declared via DeclareInputPort.
std::unique_ptr<SystemOutput<T> > AllocateOutput | ( | ) | const |
Returns a container that can hold the values of all of this System's output ports.
It is sized with the number of output ports and uses each output port's allocation method to provide an object of the right type for that port.
|
pure virtual |
Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext.
The simulator will provide this state as the output argument to EvalTimeDerivatives.
Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, and LeafSystem< AutoDiffXd >.
void ApplyDiscreteVariableUpdate | ( | const EventCollection< DiscreteUpdateEvent< T >> & | events, |
DiscreteValues< T > * | discrete_state, | ||
Context< T > * | context | ||
) | const |
Given the discrete_state
results of a previous call to CalcDiscreteVariableUpdate() that dispatched the given collection of events, modifies the context
to reflect the updated discrete_state
.
[in] | events | The Event collection that resulted in the given discrete_state . |
[in,out] | discrete_state | The updated discrete state from a CalcDiscreteVariableUpdate() call. This is mutable to permit its contents to be swapped with the corresponding context contents (rather than copied). |
[in,out] | context | The Context whose discrete state is modified to match discrete_state . Note that swapping contents with discrete_state may cause addresses of individual discrete state group vectors in context to be different on return than they were on entry. |
discrete_state
is the result of a previous CalcDiscreteVariableUpdate() call that dispatched this events
collection. void ApplyUnrestrictedUpdate | ( | const EventCollection< UnrestrictedUpdateEvent< T >> & | events, |
State< T > * | state, | ||
Context< T > * | context | ||
) | const |
Given the state
results of a previous call to CalcUnrestrictedUpdate() that dispatched the given collection of events, modifies the context
to reflect the updated state
.
[in] | events | The Event collection that resulted in the given state . |
[in,out] | state | The updated State from a CalcUnrestrictedUpdate() call. This is mutable to permit its contents to be swapped with the corresponding context contents (rather than copied). |
[in,out] | context | The Context whose State is modified to match state . Note that swapping contents with the state may cause addresses of continuous, discrete, and abstract state containers in context to be different on return than they were on entry. |
state
is the result of a previous CalcUnrestrictedUpdate() call that dispatched this events
collection. DependencyTicket cache_entry_ticket |
Returns a ticket indicating dependence on the cache entry indicated by index
.
Note that cache entries are not included in the all_sources
ticket so must be listed separately.
index
selects an existing cache entry in this System. T CalcConservativePower | ( | const Context< T > & | context | ) | const |
Calculates and returns the conservative power represented by the current contents of the given context
.
Prefer EvalConservativePower() to avoid unnecessary recalculation.
EventStatus CalcDiscreteVariableUpdate | ( | const Context< T > & | context, |
const EventCollection< DiscreteUpdateEvent< T >> & | events, | ||
DiscreteValues< T > * | discrete_state | ||
) | const |
This method is the public entry point for dispatching all discrete variable update event handlers.
Using all the discrete update handlers in events
, the method calculates the update xd(n+1)
to discrete variables xd(n)
in context
and outputs the results to discrete_state
. See documentation for DispatchDiscreteVariableUpdateHandler() for more details.
void CalcForcedDiscreteVariableUpdate | ( | const Context< T > & | context, |
DiscreteValues< T > * | discrete_state | ||
) | const |
(Advanced) Manually triggers any DiscreteUpdateEvent that has trigger type kForced.
Invokes the discrete event dispatcher on this System with the given Context providing the initial values for the discrete variables. The updated values of the discrete variables are written to the discrete_state
output argument; no change is made to the Context.
The default dispatcher will invoke the handlers (if any) associated with each force-triggered event.
std::exception | if it invokes an event handler that returns status indicating failure. |
(Advanced) Manually triggers any UnrestrictedUpdateEvent that has trigger type kForced.
Invokes the unrestricted event dispatcher on this System with the given Context providing the initial values for the state variables. The updated values of the state variables are written to the state
output argument; no change is made to the Context.
The default dispatcher will invoke the handlers (if any) associated with each force-triggered event.
std::exception | if it invokes an event handler that returns status indicating failure. |
void CalcImplicitTimeDerivativesResidual | ( | const Context< T > & | context, |
const ContinuousState< T > & | proposed_derivatives, | ||
EigenPtr< VectorX< T >> | residual | ||
) | const |
Evaluates the implicit form of the System equations and returns the residual.
The explicit and implicit forms of the System equations are
(1) ẋ꜀ = fₑ(𝓒) explicit (2) 0 = fᵢ(𝓒; ẋ꜀) implicit
where 𝓒 = {a, p, t, x, u}
is the current value of the given Context from which accuracy a, parameters p, time t, state x (={x꜀ xd xₐ}
) and input values u are obtained. Substituting (1) into (2) shows that the following condition must always hold:
(3) fᵢ(𝓒; fₑ(𝓒)) = 0 always true
When fᵢ(𝓒; ẋ꜀ₚ)
is evaluated with a proposed time derivative ẋ꜀ₚ that differs from ẋ꜀ the result will be non-zero; we call that the residual of the implicit equation. Given a Context and proposed time derivative ẋ꜀ₚ, this method returns the residual r such that
(4) r = fᵢ(𝓒; ẋ꜀ₚ).
The returned r will typically be the same length as x꜀ although that is not required. And even if r and x꜀ are the same size, there will not necessarily be any elementwise correspondence between them. (That is, you should not assume that r[i] is the "residual" of ẋ꜀ₚ[i].) For a Diagram, r is the concatenation of residuals from each of the subsystems, in order of subsystem index within the Diagram.
A default implementation fᵢ⁽ᵈᵉᶠ⁾ for the implicit form is always provided and makes use of the explicit form as follows:
(5) fᵢ⁽ᵈᵉᶠ⁾(𝓒; ẋ꜀ₚ) ≜ ẋ꜀ₚ − fₑ(𝓒)
which satisfies condition (3) by construction. (Note that the default implementation requires the residual to have the same size as x꜀.) Substantial efficiency gains can often be obtained by replacing the default function with a customized implementation. Override DoCalcImplicitTimeDerivativesResidual() to replace the default implementation with a better one.
[in] | context | The source for time, state, inputs, etc. to be used in calculating the residual. |
[in] | proposed_derivatives | The proposed value ẋ꜀ₚ for the time derivatives of x꜀. |
[out] | residual | The result r of evaluating the implicit function. Can be any mutable Eigen vector object of size implicit_time_derivatives_residual_size(). |
proposed_derivatives
is compatible with this System. residual
is of size implicit_time_derivatives_residual_size().T CalcKineticEnergy | ( | const Context< T > & | context | ) | const |
Calculates and returns the kinetic energy represented by the current configuration and velocity provided in context
.
Prefer EvalKineticEnergy() to avoid unnecessary recalculation.
T CalcNextUpdateTime | ( | const Context< T > & | context, |
CompositeEventCollection< T > * | events | ||
) | const |
This method is called by a Simulator during its calculation of the size of the next continuous step to attempt.
The System returns the next time at which some discrete action must be taken, and records what those actions ought to be in events
. Upon reaching that time, the simulator will merge events
with the other CompositeEventCollection instances triggered through other mechanisms (e.g. GetPerStepEvents()), and the merged CompositeEventCollection will be passed to all event handling mechanisms.
Despite the name, the returned events includes both state-updating events and publish events.
If there is no timed event coming, the return value is Infinity. If a finite update time is returned, there will be at least one Event object in the returned event collection.
events
cannot be null. events
will be cleared on entry.
T CalcNonConservativePower | ( | const Context< T > & | context | ) | const |
Calculates and returns the non-conservative power represented by the current contents of the given context
.
Prefer EvalNonConservativePower() to avoid unnecessary recalculation.
void CalcOutput | ( | const Context< T > & | context, |
SystemOutput< T > * | outputs | ||
) | const |
Utility method that computes for every output port i the value y(i) that should result from the current contents of the given Context.
Note that individual output port values can be calculated using get_output_port(i).Calc()
; this method invokes that for each output port in index order. The result may depend on time and the current values of input ports, parameters, and state variables. The result is written to outputs
which must already have been allocated to have the right number of entries of the right types.
T CalcPotentialEnergy | ( | const Context< T > & | context | ) | const |
Calculates and returns the potential energy represented by the current configuration provided in context
.
Prefer EvalPotentialEnergy() to avoid unnecessary recalculation.
void CalcTimeDerivatives | ( | const Context< T > & | context, |
ContinuousState< T > * | derivatives | ||
) | const |
Calculates the time derivatives ẋ꜀ of the continuous state x꜀ into a given output argument.
Prefer EvalTimeDerivatives() instead to avoid unnecessary recomputation.
This method solves the System equations in explicit form:
ẋ꜀ = fₑ(𝓒)
where 𝓒 = {a, p, t, x, u}
is the current value of the given Context from which accuracy a, parameters p, time t, state x (={x꜀ xd xₐ}
) and input values u are obtained.
[in] | context | The source for time, state, inputs, etc. defining the point at which the derivatives should be calculated. |
[out] | derivatives | The time derivatives ẋ꜀. Must be the same size as the continuous state vector in context . |
EventStatus CalcUnrestrictedUpdate | ( | const Context< T > & | context, |
const EventCollection< UnrestrictedUpdateEvent< T >> & | events, | ||
State< T > * | state | ||
) | const |
This method is the public entry point for dispatching all unrestricted update event handlers.
Using all the unrestricted update handlers in events
, it updates any state variables in the context
, and outputs the results to state
. It does not allow the dimensionality of the state variables to change. See the documentation for DispatchUnrestrictedUpdateHandler() for more details.
std::exception | if the dimensionality of the state variables changes in the callback. |
T CalcWitnessValue | ( | const Context< T > & | context, |
const WitnessFunction< T > & | witness_func | ||
) | const |
Evaluates a witness function at the given context.
Returns true if context
satisfies all of the registered SystemConstraints with tolerance tol
.
std::unique_ptr<System<T> > Clone | ( | ) | const |
Creates a deep copy of this system.
Even though the cloned system is functionally identical, any contexts created for this system are not compatible with the cloned system, and vice versa.
The result is never nullptr.
|
static |
Creates a deep copy of this system.
In contrast with the instance member function sys.Clone()
, this static member function Clone(sys)
is useful for C++ users to preserve the declared type of the system being cloned in the returned pointer. (For both clone overloads, the runtime type is always the same.)
Even though the cloned system is functionally identical, any contexts created for this system are not compatible with the cloned system, and vice versa.
The result is never nullptr.
Usage:
S | The specific System type to accept and return. |
|
static |
Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations.
In particular, this category does not include time, generalized velocities v, miscellaneous continuous state variables z, or input ports. Generalized coordinates q are included, as well as any discrete state variables that have been declared as configuration variables, and configuration-affecting parameters. Finally we assume that the accuracy setting may affect some configuration-dependent computations. Examples: a parameter that affects length may change the computation of an end-effector location. A change in accuracy requirement may require recomputation of an iterative approximation of contact forces.
Returns a copy of the continuous state vector x꜀ into an Eigen vector.
std::unique_ptr<Context<T> > CreateDefaultContext | ( | ) | const |
This convenience method allocates a context using AllocateContext() and sets its default values using SetDefaultContext().
|
protected |
Declares a cache entry by specifying a model value of concrete type ValueType
and a calculator function that is a class member function (method) with signature:
where MySystem
is a class derived from SystemBase
, MyContext
is a class derived from ContextBase
, and ValueType
is any concrete type such that Value<ValueType>
is permitted. (The method names are arbitrary.) Template arguments will be deduced and do not need to be specified. See the primary DeclareCacheEntry() signature above for more information about the parameters and behavior.
|
protected |
Declares a new CacheEntry in this System using the most generic form of the calculation function.
Prefer one of the more convenient signatures below if you can. The new cache entry is assigned a unique CacheIndex and DependencyTicket, which can be obtained from the returned CacheEntry.
[in] | description | A human-readable description of this cache entry, most useful for debugging and documentation. Not interpreted in any way by Drake; it is retained by the cache entry and used to generate the description for the corresponding CacheEntryValue in the Context. |
[in] | value_producer | Provides the computation that maps from a given Context to the current value that this cache entry should have, as well as a way to allocate storage prior to the computation. |
[in] | prerequisites_of_calc | Provides the DependencyTicket list containing a ticket for every Context value on which calc_function may depend when it computes its result. Defaults to {all_sources_ticket()} if unspecified. If the cache value is truly independent of the Context (rare!) say so explicitly by providing the list {nothing_ticket()} ; an explicitly empty list {} is forbidden. |
std::exception | if given an explicitly empty prerequisite list. |
|
protected |
Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature:
where MySystem
is a class derived from SystemBase
and MyContext
is a class derived from ContextBase
. ValueType
is a concrete type such that (a) Value<ValueType>
is permitted, and (b) ValueType
is default constructible. That allows us to create a model value using Value<ValueType>{}
(value initialized so numerical types will be zeroed in the model). (The method name is arbitrary.) Template arguments will be deduced and do not need to be specified. See the first DeclareCacheEntry() signature above for more information about the parameters and behavior.
ValueType
default constructor each time it is called.
|
protected |
Adds a port with the specified type
and size
to the input topology.
Input port names must be unique for this system (passing in a duplicate name
will throw std::exception). If name
is given as kUseDefaultName, then a default value of e.g. "u2", where 2 is the input number will be provided. An empty name
is not permitted.
If the port is intended to model a random noise or disturbance input, random_type
can (optionally) be used to label it as such; doing so enables algorithms for design and analysis (e.g. state estimation) to reason explicitly about randomness at the system level. All random input ports are assumed to be statistically independent.
name
must not be empty. std::exception | for a duplicate port name. |
DependencyTicket discrete_state_ticket |
Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector).
(We sometimes refer to this as a "discrete variable group".)
|
protectedpure virtual |
(Internal use only) This function dispatches all discrete update events to the appropriate handlers.
discrete_state
cannot be null. Only LeafSystem and Diagram (and some unit test code) provide implementations and those must be final
.
|
protectedpure virtual |
(Internal use only) This function dispatches all publish events to the appropriate handlers.
Only LeafSystem and Diagram (and some unit test code) provide implementations and those must be final
.
|
protectedpure virtual |
(Internal use only) This function dispatches all unrestricted update events to the appropriate handlers.
state
cannot be null. Only LeafSystem and Diagram (and some unit test code) provide implementations and those must be final
.
|
protectedpure virtual |
(Internal use only) Updates the given context
with the results returned from a previous call to DispatchDiscreteVariableUpdateHandler() that handled the given events
.
|
protectedpure virtual |
(Internal use only) Updates the given context
with the results returned from a previous call to DispatchUnrestrictedUpdateHandler() that handled the given events
.
|
protectedvirtual |
Override this method to return the rate Pc at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context.
By default, returns zero. Physical systems should override. You may assume that context
has already been validated before it is passed to you here.
See EvalConservativePower() for details on what you must compute here. In particular, this quantity must be positive when potential energy is decreasing, and your conservative power method must not depend explicitly on time or any input port values.
Reimplemented in SpringMassSystem< T >, and SpringMassSystem< double >.
|
protectedvirtual |
Override this if you have an efficient way to evaluate the implicit time derivatives residual for this System.
Otherwise the default implementation is residual = proposed_derivatives − EvalTimeDerivatives(context)
. Note that you cannot use the default implementation if you have changed the declared residual size.
proposed_derivatives
is compatible with this System and that residual
is non-null and of the declared size (as reported by SystemBase::implicit_time_derivatives_residual_size()). You do not have to check those two conditions in your implementation, but if you have additional restrictions you should validate that they are also met.
|
protectedvirtual |
Override this method for physical systems to calculate the kinetic energy KE currently present in the motion provided in the given Context.
The default implementation returns 0 which is correct for non-physical systems. You may assume that context
has already been validated before it is passed to you here.
See EvalKineticEnergy() for details on what you must compute here. In particular, your kinetic energy method must not depend explicitly on time or any input port values.
Reimplemented in SpringMassSystem< T >, and SpringMassSystem< double >.
|
protectedvirtual |
Computes the next time at which this System must perform a discrete action.
Override this method if your System has any discrete actions which must interrupt the continuous simulation. This method is called only from the public non-virtual CalcNextUpdateTime() which will already have error-checked the parameters so you don't have to. You may assume that context
has already been validated and events
pointer is not null.
If you override this method, you must set the returned time
. Set it to Infinity if there are no upcoming timed events. If you return a finite update time, you must put at least one Event object in the events
collection. These requirements are enforced by the public CalcNextUpdateTime() method.
The default implementation returns with the next sample time being Infinity and no events added to events
.
Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, LeafSystem< AutoDiffXd >, and LcmLogPlaybackSystem.
|
protectedvirtual |
Override this method to return the rate Pnc at which work W is done on the system by non-conservative forces.
By default, returns zero. Physical systems should override. You may assume that context
has already been validated before it is passed to you here.
See EvalNonConservativePower() for details on what you must compute here. In particular, this quantity must be negative if the non-conservative forces are dissipative, positive otherwise. Your non-conservative power method can depend on anything you find in the given Context, including time and input ports.
Reimplemented in SpringMassSystem< T >, and SpringMassSystem< double >.
|
protectedvirtual |
Override this method for physical systems to calculate the potential energy PE currently stored in the configuration provided in the given Context.
The default implementation returns 0 which is correct for non-physical systems. You may assume that context
has already been validated before it is passed to you here.
See EvalPotentialEnergy() for details on what you must compute here. In particular, your potential energy method must not depend explicitly on time, velocities, or any input port values.
Reimplemented in SpringMassSystem< T >, and SpringMassSystem< double >.
|
protectedvirtual |
Override this if you have any continuous state variables x꜀ in your concrete System to calculate their time derivatives.
The derivatives
vector will correspond elementwise with the state vector Context.state.continuous_state.get_state()
. Thus, if the state in the Context has second-order structure x꜀=[q v z]
, that same structure applies to the derivatives.
This method is called only from the public non-virtual CalcTimeDerivatives() which will already have error-checked the parameters so you don't have to. In particular, implementations may assume that the given Context is valid for this System; that the derivatives
pointer is non-null, and that the referenced object has the same constituent structure as was produced by AllocateTimeDerivatives().
The default implementation does nothing if the derivatives
vector is size zero and aborts otherwise.
Reimplemented in SpringMassSystem< T >, SpringMassSystem< double >, PidController< T >, VectorSystem< T >, TimeVaryingAffineSystem< T >, TimeVaryingAffineSystem< double >, SpringMassDamperSystem< T >, SpringMassDamperSystem< double >, StiffDoubleMassSpringSystem< T >, StiffDoubleMassSpringSystem< double >, PleidesSystem, DiscontinuousSpringMassDamperSystem< T >, DiscontinuousSpringMassDamperSystem< double >, RobertsonSystem< T >, and StationarySystem< T >.
|
protectedpure virtual |
Derived classes will implement this method to evaluate a witness function at the given context.
Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, and LeafSystem< AutoDiffXd >.
|
protectedvirtual |
Implement this method to return any events to be handled at the simulator's initialization step.
events
is cleared in the public non-virtual GetInitializationEvents(). You may assume that context
has already been validated and that events
is not null. events
can be changed freely by the overriding implementation.
The default implementation returns without changing events
.
|
protectedvirtual |
Implement this method to return any periodic events.
events
is cleared in the public non-virtual GetPeriodicEvents(). You may assume that context
has already been validated and that events
is not null. events
can be changed freely by the overriding implementation.
The default implementation returns without changing events
.
|
protectedvirtual |
Implement this method to return any events to be handled before the simulator integrates the system's continuous state at each time step.
events
is cleared in the public non-virtual GetPerStepEvents() before that method calls this function. You may assume that context
has already been validated and that events
is not null. events
can be changed freely by the overriding implementation.
The default implementation returns without changing events
.
|
protectedvirtual |
Derived classes can override this method to provide witness functions active for the given state.
The default implementation does nothing. On entry to this function, the context will have already been validated and the vector of witness functions will have been validated to be both empty and non-null.
Reimplemented in Diagram< T >, Diagram< double >, and StatelessSystem< T >.
|
protectedpure virtual |
Implement this method to return all periodic triggered events organized by timing.
|
protectedvirtual |
Provides the substantive implementation of MapQDotToVelocity().
The default implementation uses the identity mapping, and correctly does nothing if the System does not have second-order state variables. It throws std::exception if the generalized_velocity
and qdot
are not the same size, but that is not enough to guarantee that the default implementation is adequate. Child classes must override this function if qdot != v (even if they are the same size). This occurs, for example, if a joint uses roll-pitch-yaw rotation angles for orientation but angular velocity for rotational rate rather than rotation angle derivatives.
If you implement this method you are required to use no more than O(nq)
time where nq
is the size of qdot
, so that the System can meet the performance guarantee made for the public interface, and you must also implement DoMapVelocityToQDot(). Implementations may assume that qdot
has already been validated to be the same size as q
in the given Context, and that generalized_velocity
is non-null.
Reimplemented in Diagram< T >, and Diagram< double >.
|
protectedvirtual |
Provides the substantive implementation of MapVelocityToQDot().
The default implementation uses the identity mapping, and correctly does nothing if the System does not have second-order state variables. It throws std::exception if the generalized_velocity
(v
) and qdot
are not the same size, but that is not enough to guarantee that the default implementation is adequate. Child classes must override this function if qdot != v
(even if they are the same size). This occurs, for example, if a joint uses roll-pitch-yaw rotation angles for orientation but angular velocity for rotational rate rather than rotation angle derivatives.
If you implement this method you are required to use no more than O(nq)
time where nq
is the size of qdot
, so that the System can meet the performance guarantee made for the public interface, and you must also implement DoMapQDotToVelocity(). Implementations may assume that generalized_velocity
has already been validated to be the same size as v
in the given Context, and that qdot
is non-null.
Reimplemented in Diagram< T >, and Diagram< double >.
const T& EvalConservativePower | ( | const Context< T > & | context | ) | const |
Returns a reference to the cached value of the conservative power (Pc), evaluating first if necessary using CalcConservativePower().
The returned Pc represents the rate at which mechanical energy is being converted from potential energy (PE) to kinetic energy (KE) by this system in the given Context. This quantity will be positive when PE is decreasing. By definition here, conservative power may depend only on quantities that explicitly contribute to PE and KE. See EvalPotentialEnergy() and EvalKineticEnergy() for details.
Power due to non-conservative forces (e.g. dampers) can contribute to the rate of change of KE. Therefore this method alone cannot be used to determine whether KE is increasing or decreasing, only whether the conservative power is adding or removing kinetic energy. EvalNonConservativePower() can be used in conjunction with this method to find the total rate of change of KE.
Non-physical systems where Pc is not meaningful will return Pc = 0.
context | The Context whose contents may be used to evaluate conservative power. |
Pc | The conservative power in watts (W or J/s) represented by the contents of the given context . |
const T& EvalKineticEnergy | ( | const Context< T > & | context | ) | const |
Returns a reference to the cached value of the kinetic energy (KE), evaluating first if necessary using CalcKineticEnergy().
By definition here, kinetic energy depends only on "configuration" and "velocity" (e.g. angular and translational velocity) of moving masses which includes a subset of the state variables, and parameters that affect configuration, velocities, or mass properties. The calculated value may also be affected by the accuracy value supplied in the Context. KE cannot depend explicitly on time (∂KE/∂t = 0) or input port values (∂KE/∂u = 0).
Non-physical systems where KE is not meaningful will return KE = 0.
context | The Context whose configuration and velocity variables may be used to evaluate kinetic energy. |
KE | The kinetic energy in joules (J) represented by the configuration and velocity given in context . |
const T& EvalNonConservativePower | ( | const Context< T > & | context | ) | const |
Returns a reference to the cached value of the non-conservative power (Pnc), evaluating first if necessary using CalcNonConservativePower().
The returned Pnc represents the rate at which work W is done on the system by non-conservative forces. Pnc is negative if the non-conservative forces are dissipative, positive otherwise. Time integration of Pnc yields work W, and the total mechanical energy E = PE + KE − W
should be conserved by any physically-correct model, to within integration accuracy of W. Power is in watts (J/s). (Watts are abbreviated W but not to be confused with work!) Any values in the supplied Context (including time and input ports) may contribute to the computation of non-conservative power.
Non-physical systems where Pnc is not meaningful will return Pnc = 0.
context | The Context whose contents may be used to evaluate non-conservative power. |
Pnc | The non-conservative power in watts (W or J/s) represented by the contents of the given context . |
const T& EvalPotentialEnergy | ( | const Context< T > & | context | ) | const |
Returns a reference to the cached value of the potential energy (PE), evaluating first if necessary using CalcPotentialEnergy().
By definition here, potential energy depends only on "configuration" (e.g. orientation and position), which includes a subset of the state variables, and parameters that affect configuration or conservative forces (such as lengths and masses). The calculated value may also be affected by the accuracy value supplied in the Context. PE cannot depend explicitly on time (∂PE/∂t = 0), velocities (∂PE/∂v = 0), or input port values (∂PE/∂u = 0).
Non-physical systems where PE is not meaningful will return PE = 0.
context | The Context whose configuration variables may be used to evaluate potential energy. |
PE | The potential energy in joules (J) represented by the configuration given in context . |
const ContinuousState<T>& EvalTimeDerivatives | ( | const Context< T > & | context | ) | const |
Returns a reference to the cached value of the continuous state variable time derivatives, evaluating first if necessary using CalcTimeDerivatives().
This method returns the time derivatives ẋ꜀ of the continuous state x꜀. The referenced return object will correspond elementwise with the continuous state in the given Context. Thus, if the state in the Context has second-order structure x꜀ = [q v z]
, that same structure applies to the derivatives so we will have ẋ꜀ = [q̇ ̇v̇ ż]
.
context | The Context whose time, input port, parameter, state, and accuracy values may be used to evaluate the derivatives. |
xcdot | Time derivatives ẋ꜀ of x꜀ returned as a reference to an object of the same type and size as context 's continuous state. |
const DiscreteValues<T>& EvalUniquePeriodicDiscreteUpdate | ( | const Context< T > & | context | ) | const |
If this System contains a unique periodic timing for discrete update events, this function executes the handlers for those periodic events to determine what their effect would be.
Returns a reference to the discrete variable cache entry containing what values the discrete variables would have if these periodic events were triggered.
Note that this function does not change the value of the discrete variables in the supplied Context. However, you can apply the result to the Context like this:
You can write the updated values to a different Context than the one you used to calculate the update; the requirement is only that the discrete state in the destination has the same structure (number of groups and size of each group).
You can use GetUniquePeriodicDiscreteUpdateAttribute() to check whether you can call EvalUniquePeriodicDiscreteUpdate() safely, and to find the unique periodic timing information (offset and period).
[in] | context | The Context containing the current System state and the mutable cache space into which the result is written. The current state is not modified, though the cache entry may be updated. |
context
containing the result of applying the discrete update event handlers to the current discrete variable values.std::exception | if there is not exactly one periodic timing in this System (which may be a Diagram) that triggers discrete update events. |
std::exception | if it invokes an event handler that returns status indicating failure. |
context
cache space. Applies the discrete update event handlers (in an unspecified order) to the cache copy, possibly updating it. Returns a reference to the possibly-updated cache space.Returns the value of the vector-valued input port with the given port_index
as a BasicVector or a specific subclass Vec
derived from BasicVector.
Causes the value to become up to date first if necessary. See EvalAbstractInput() for more information.
The result is returned as a pointer to the input port's value of type Vec<T>
or nullptr if the port is not connected.
port_index
selects an existing input port of this System. Vec | The template type of the input vector, which must be a subclass of BasicVector. |
void ExecuteForcedEvents | ( | Context< T > * | context, |
bool | publish = true |
||
) | const |
This method triggers all of the forced events registered with this System (which might be a Diagram).
Ordering and status return handling mimic the Simulator: unrestricted events are processed first, then discrete update events, then publish events. "Reached termination" status returns are ignored.
An option is provided to suppress publish events. This can be useful, for example, to update state in a Diagram without triggering a visualization.
[in,out] | context | The Context supplied to the handlers and modified in place on return. |
std::exception | if it invokes an event handler that returns status indicating failure. |
void ExecuteInitializationEvents | ( | Context< T > * | context | ) | const |
This method triggers all of the initialization events returned by GetInitializationEvents().
The method allocates temporary storage to perform the updates, and is intended only as a convenience method for callers who do not want to use the full Simulator workflow.
Note that this is not fully equivalent to Simulator::Initialize() because only initialization events are handled here, while Simulator::Initialize() also processes other events associated with time zero. Also, "reached termination" returns are ignored here.
[in,out] | context | The Context supplied to the handlers and modified in place on return. |
std::exception | if it invokes an event handler that returns status indicating failure. |
|
staticprotected |
(Internal use only) Static interface to DoFindUniquePeriodicDiscreteUpdatesOrThrow() to allow a Diagram to invoke that private method on its subsystems.
void FixInputPortsFrom | ( | const System< double > & | other_system, |
const Context< double > & | other_context, | ||
Context< T > * | target_context | ||
) | const |
Fixes all of the input ports in target_context
to their current values in other_context
, as evaluated by other_system
.
std::exception | unless other_context and target_context both have the same shape as this System, and the other_system . Ignores disconnected inputs. |
std::exception | if this system's scalar type T != double and other_system has any abstract input ports whose contained type depends on scalar type. |
|
protected |
|
protected |
|
protected |
void ForcedPublish | ( | const Context< T > & | context | ) | const |
(Advanced) Manually triggers any PublishEvent that has trigger type kForced.
Invokes the publish event dispatcher on this System with the given Context.
The default dispatcher will invoke the handlers (if any) associated with each force-triggered event.
The Simulator can be configured to call this in Simulator::Initialize() and at the start of each continuous integration step. See the Simulator API for more details.
std::exception | if it invokes an event handler that returns status indicating failure. |
const SystemConstraint<T>& get_constraint | ( | SystemConstraintIndex | constraint_index | ) | const |
Returns the constraint at index constraint_index
.
std::exception | for an invalid constraint_index. |
|
protected |
|
protected |
Returns the typed input port at index port_index
.
warn_deprecated | Whether or not to print a warning in case the port was marked as deprecated. |
const InputPort<T>& get_input_port | ( | ) | const |
Convenience method for the case of exactly one input port.
This function ignores deprecated ports, unless there is only one port in which case it will return the deprecated port.
const InputPort<T>* get_input_port_selection | ( | std::variant< InputPortSelection, InputPortIndex > | port_index | ) | const |
Returns the typed input port specified by the InputPortSelection or by the InputPortIndex.
Returns nullptr if no port is selected. This is provided as a convenience method since many algorithms provide the same common default or optional port semantics.
|
protected |
|
protected |
|
protected |
|
protected |
Returns the SystemScalarConverter for this
system.
const OutputPort<T>& get_output_port | ( | int | port_index, |
bool | warn_deprecated = true |
||
) | const |
Returns the typed output port at index port_index
.
warn_deprecated | Whether or not to print a warning in case the port was marked as deprecated. |
const OutputPort<T>& get_output_port | ( | ) | const |
Convenience method for the case of exactly one output port.
This function ignores deprecated ports, unless there is only one port in which case it will return the deprecated port.
const OutputPort<T>* get_output_port_selection | ( | std::variant< OutputPortSelection, OutputPortIndex > | port_index | ) | const |
Returns the typed output port specified by the OutputPortSelection or by the OutputPortIndex.
Returns nullptr if no port is selected. This is provided as a convenience method since many algorithms provide the same common default or optional port semantics.
const SystemScalarConverter& get_system_scalar_converter | ( | ) | const |
(Advanced) Returns the SystemScalarConverter for this object.
This is an expert-level API intended for framework authors. Most users should prefer the convenience helpers such as System::ToAutoDiffXd.
const CacheEntry& get_time_derivatives_cache_entry | ( | ) | const |
(Advanced) Returns the CacheEntry used to cache time derivatives for EvalTimeDerivatives().
Reports all direct feedthroughs from input ports to output ports.
For a system with m input ports: I = i₀, i₁, ..., iₘ₋₁
, and n output ports, O = o₀, o₁, ..., oₙ₋₁
, the return map will contain pairs (u, v) such that
See DeclareLeafOutputPort documentation for how leaf systems can report their feedthrough.
std::string GetGraphvizString |
Returns a Graphviz string describing this System.
To render the string, use the Graphviz tool, dot
.
Notes about the display conventions:
name=...
.max_depth | Sets a limit to the depth of nested diagrams to visualize. Use zero to render a diagram as a single system block. |
options | Arbitrary strings to request alterations to the output. Options that are unknown will be silently skipped. These options are often bespoke flags that are only understood by particular systems, but Drake has one built-in flag that is generally applicable: "split" . When set to "I/O" , the system will be added as two nodes with all inputs on one node and all outputs on the other; this is useful for systems that might otherwise cause problematic visual cycles. |
Options are applied only to this immediate system; they are not inherited by the subsystems of a Diagram. To specify an option for a Diagram's subsystem, prefix the option name with the subsystem's path, e.g., use "plant/split"="I/O"
to set the "split"
option on the subsystem named "plant"
.
void GetInitializationEvents | ( | const Context< T > & | context, |
CompositeEventCollection< T > * | events | ||
) | const |
This method is called by Simulator::Initialize() to gather all update and publish events that need to be handled at initialization before the simulator starts integration.
events
cannot be null. events
will be cleared on entry.
const InputPort<T>& GetInputPort | ( | const std::string & | port_name | ) | const |
Returns the typed input port with the unique name port_name
.
The current implementation performs a linear search over strings; prefer get_input_port() when performance is a concern.
std::exception | if port_name is not found. |
std::string GetMemoryObjectName |
Returns a name for this System based on a stringification of its type name and memory address.
This is intended for use in diagnostic output and should not be used for behavioral logic, because the stringification of the type name may produce differing results across platforms and because the address can vary from run to run.
|
protected |
Returns a mutable Eigen expression for a vector valued output port with index port_index
in this system.
All input ports that directly depend on this output port will be notified that upstream data has changed, and may invalidate cache entries as a result.
Context<T>& GetMutableSubsystemContext | ( | const System< T > & | subsystem, |
Context< T > * | context | ||
) | const |
Returns a mutable reference to the subcontext that corresponds to the contained System subsystem
.
std::exception | if subsystem not contained in this System. |
context
is valid for use with this
System. Returns the const Context for this
subsystem, given a root context.
If this
System is already the top level (root) System, just returns root_context
. (A root Context is one that does not have a parent Context.)
std::exception | if the given root_context is not actually a root context. |
Returns the mutable subsystem context for this
system, given a root context.
const OutputPort<T>& GetOutputPort | ( | const std::string & | port_name | ) | const |
Returns the typed output port with the unique name port_name
.
The current implementation performs a linear search over strings; prefer get_output_port() when performance is a concern.
std::exception | if port_name is not found. |
void GetPeriodicEvents | ( | const Context< T > & | context, |
CompositeEventCollection< T > * | events | ||
) | const |
Returns all periodic events in this System.
This includes publish, discrete update, and unrestricted update events.
events
cannot be null. events
will be cleared on entry.
void GetPerStepEvents | ( | const Context< T > & | context, |
CompositeEventCollection< T > * | events | ||
) | const |
This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in AdvanceTo() at the point before Simulator integrates continuous state.
It is assumed that these events remain constant throughout the simulation. The "step" here refers to the major time step taken by the Simulator. During every simulation step, the simulator will merge events
with the event collections populated by other types of event triggering mechanism (e.g., CalcNextUpdateTime()), and the merged CompositeEventCollection objects will be passed to the appropriate handlers before Simulator integrates the continuous state.
events
cannot be null. events
will be cleared on entry.
const Context<T>& GetSubsystemContext | ( | const System< T > & | subsystem, |
const Context< T > & | context | ||
) | const |
Returns a const reference to the subcontext that corresponds to the contained System subsystem
.
std::exception | if subsystem not contained in this System. |
context
is valid for use with this
System. std::optional<PeriodicEventData> GetUniquePeriodicDiscreteUpdateAttribute | ( | ) | const |
Determines whether there exists a unique periodic timing (offset and period) that triggers one or more discrete update events (and, if so, returns that unique periodic timing).
Thus, this method can be used (1) as a test to determine whether a system's dynamics are at least partially governed by difference equations, and (2) to obtain the difference equation update times. Use EvalUniquePeriodicDiscreteUpdate() if you want to determine the actual effects of triggering these events.
nullopt
.void GetWitnessFunctions | ( | const Context< T > & | context, |
std::vector< const WitnessFunction< T > * > * | w | ||
) | const |
Gets the witness functions active for the given state.
DoGetWitnessFunctions() does the actual work. The vector of active witness functions are expected to change only upon an unrestricted update.
context | a valid context for the System (aborts if not true). | |
[out] | w | a valid pointer to an empty vector that will store pointers to the witness functions active for the current state. The method aborts if witnesses is null or non-empty. |
bool HasAnyDirectFeedthrough | ( | ) | const |
Returns true
if any of the inputs to the system might be directly fed through to any of its outputs and false
otherwise.
bool HasDirectFeedthrough | ( | int | output_port | ) | const |
Returns true if there might be direct-feedthrough from any input port to the given output_port
, and false otherwise.
Returns true if there might be direct-feedthrough from the given input_port
to the given output_port
, and false otherwise.
bool HasInputPort | ( | const std::string & | port_name | ) | const |
Returns true iff the system has an InputPort of the given port_name
.
bool HasOutputPort | ( | const std::string & | port_name | ) | const |
Returns true iff the system has an OutputPort of the given port_name
.
DependencyTicket input_port_ticket |
Returns a ticket indicating dependence on input port uᵢ indicated by index
.
index
selects an existing input port of this System. bool IsDifferenceEquationSystem | ( | double * | time_period = nullptr | ) | const |
Returns true iff the state dynamics of this system are governed exclusively by a difference equation on a single discrete state group and with a unique periodic update (having zero offset).
E.g., it is amenable to analysis of the form:
x[n+1] = f(n, x[n], u[n], w[n]; p)
where t is time, x is (discrete) state, u is a vector input, w is random (disturbance) input, and p are parameters. Note that we do NOT consider the number of input ports here, because in practice many systems of interest (e.g. MultibodyPlant) have input ports that are safely treated as constant during the analysis. Consider using get_input_port_selection() to choose one.
[out] | time_period | if non-null, then iff the function returns true , then time_period is set to the period data returned from GetUniquePeriodicDiscreteUpdateAttribute(). If the function returns false (the system is not a difference equation system), then time_period does not receive a value. |
bool IsDifferentialEquationSystem | ( | ) | const |
Returns true iff the state dynamics of this system are governed exclusively by a differential equation.
E.g., it is amenable to analysis of the form:
ẋ = f(t, x(t), u(t), w(t); p),
where t is time, x is (continuous) state, u is a vector input, w is random (disturbance) input, and p are parameters. This requires that it has no discrete nor abstract states, and no abstract input ports.
|
static |
Returns a ticket for the cache entry that holds the kinetic energy calculation.
|
static |
Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations.
This ticket depends on the configuration_ticket defined above, and adds in velocity-affecting source values. This does not include time or input ports.
std::map<PeriodicEventData, std::vector<const Event<T>*>, PeriodicEventDataComparator> MapPeriodicEventsByTiming | ( | const Context< T > * | context = nullptr | ) | const |
Maps all periodic triggered events for a System, organized by timing.
Each unique periodic timing attribute (offset and period) is mapped to the set of Event objects that are triggered with that timing. Those may include a mix of Publish, DiscreteUpdate, and UnrestrictedUpdate events.
void MapQDotToVelocity | ( | const Context< T > & | context, |
const VectorBase< T > & | qdot, | ||
VectorBase< T > * | generalized_velocity | ||
) | const |
Transforms the time derivative qdot
of the generalized configuration q
to generalized velocities v
.
v
and qdot
are related linearly by qdot = N(q) * v
, where N
is a block diagonal matrix. For example, in a multibody system there will be one block of N
per tree joint. Although N
is not necessarily square, its left pseudo-inverse N+
can be used to invert that relationship without residual error, provided that qdot
is in the range space of N
(that is, if it could have been produced as qdot=N*v
for some v
). Using the configuration q
from the given Context this method calculates v = N+ * qdot
(where N+=N+(q)
) for a given qdot
. This computation requires only O(nq)
time where nq
is the size of qdot
. Note that this method does not take qdot
from the Context.
See the alternate signature if you already have qdot
in an Eigen VectorX object; this signature will copy the VectorBase into an Eigen object before performing the computation.
void MapQDotToVelocity | ( | const Context< T > & | context, |
const Eigen::Ref< const VectorX< T >> & | qdot, | ||
VectorBase< T > * | generalized_velocity | ||
) | const |
Transforms the given time derivative qdot
of generalized configuration q
to generalized velocity v
.
This signature takes qdot
as an Eigen VectorX object for faster speed. See the other signature of MapQDotToVelocity() for additional information.
void MapVelocityToQDot | ( | const Context< T > & | context, |
const VectorBase< T > & | generalized_velocity, | ||
VectorBase< T > * | qdot | ||
) | const |
Transforms a given generalized velocity v
to the time derivative qdot
of the generalized configuration q
taken from the supplied Context.
v
and qdot
are related linearly by qdot = N(q) * v
, where N
is a block diagonal matrix. For example, in a multibody system there will be one block of N
per tree joint. This computation requires only O(nq)
time where nq
is the size of qdot
. Note that v
is not taken from the Context; it is given as an argument here.
See the alternate signature if you already have the generalized velocity in an Eigen VectorX object; this signature will copy the VectorBase into an Eigen object before performing the computation.
void MapVelocityToQDot | ( | const Context< T > & | context, |
const Eigen::Ref< const VectorX< T >> & | generalized_velocity, | ||
VectorBase< T > * | qdot | ||
) | const |
Transforms the given generalized velocity to the time derivative of generalized configuration.
See the other signature of MapVelocityToQDot() for more information.
|
static |
Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant.
If this appears in a prerequisite list, it must be the only entry.
int num_constraints | ( | ) | const |
Returns the number of constraints specified for the system.
int num_input_ports |
Returns the number of input ports currently allocated in this System.
These are indexed from 0 to num_input_ports()-1.
int num_output_ports |
Returns the number of output ports currently allocated in this System.
These are indexed from 0 to num_output_ports()-1.
DependencyTicket numeric_parameter_ticket |
Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector).
|
static |
Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context.
|
static |
Returns a ticket for the cache entry that holds the conservative power calculation.
|
static |
Returns a ticket for the cache entry that holds the potential energy calculation.
|
static |
Returns a ticket indicating dependence on all of the numerical parameters in the current Context.
|
static |
Returns a ticket for the cache entry that holds the non-conservative power calculation.
EventStatus Publish | ( | const Context< T > & | context, |
const EventCollection< PublishEvent< T >> & | events | ||
) | const |
This method is the public entry point for dispatching all publish event handlers.
It checks the validity of context
, and directly calls DispatchPublishHandler. events
is a homogeneous collection of publish events.
|
static |
Returns a ticket indicating that a computation depends on configuration state variables q.
There is no ticket representing just one of the state variables qᵢ.
|
protected |
|
protected |
|
protected |
void SetDefaultContext | ( | Context< T > * | context | ) | const |
Sets Context fields to their default values.
User code should not override.
|
pure virtual |
Assigns default values to all parameters.
Overrides must not change the number of parameters.
parameters
may be a mutable view into context
. Don't assume that evaluating context
will be independent of writing to parameters
. Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, and LeafSystem< AutoDiffXd >.
|
pure virtual |
Assigns default values to all elements of the state.
Overrides must not change the number of state variables. The context's default parameters will have already been set.
state
may be a mutable view into context
. Don't assume that evaluating context
will be independent of writing to state
. Implemented in MultibodyPlant< double >, TimeVaryingAffineSystem< T >, TimeVaryingAffineSystem< double >, Diagram< T >, Diagram< double >, StiffDoubleMassSpringSystem< T >, StiffDoubleMassSpringSystem< double >, LeafSystem< T >, LeafSystem< Element::T >, LeafSystem< double >, LeafSystem< AutoDiffXd >, RobertsonSystem< T >, and PleidesSystem.
void SetRandomContext | ( | Context< T > * | context, |
RandomGenerator * | generator | ||
) | const |
Sets Context fields to random values.
User code should not override.
|
virtual |
Assigns random values to all parameters.
This default implementation calls SetDefaultParameters; override this method to provide random parameters using the stdc++ random library, e.g.:
Overrides must not change the number of state variables.
Reimplemented in MultilayerPerceptron< T >, Diagram< T >, and Diagram< double >.
|
virtual |
Assigns random values to all elements of the state.
This default implementation calls SetDefaultState; override this method to provide random initial conditions using the stdc++ random library, e.g.:
Overrides must not change the number of state variables.
Reimplemented in MultibodyPlant< double >, TimeVaryingAffineSystem< T >, TimeVaryingAffineSystem< double >, Diagram< T >, and Diagram< double >.
|
static |
Returns a ticket indicating dependence on time.
This is the same ticket for all systems and refers to the same time value.
std::unique_ptr<System<AutoDiffXd> > ToAutoDiffXd | ( | ) | const |
Creates a deep copy of this System, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives.
The result is never nullptr.
std::exception | if this System does not support autodiff |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
|
static |
Creates a deep copy of from
, transmogrified to use the autodiff scalar type, with a dynamic-sized vector of partial derivatives.
The result is never nullptr.
std::exception | if from does not support autodiff |
Usage:
S | The specific System type to accept and return. |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
std::unique_ptr<System<AutoDiffXd> > ToAutoDiffXdMaybe | ( | ) | const |
Creates a deep copy of this system exactly like ToAutoDiffXd(), but returns nullptr if this System does not support autodiff, instead of throwing an exception.
std::unique_ptr<System<U> > ToScalarType | ( | ) | const |
Creates a deep copy of this System, transmogrified to use the scalar type selected by a template parameter.
The result is never nullptr.
std::exception | if this System does not support the destination type. |
U | The destination scalar type. For a list of supported types, see the default scalars. |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
|
static |
Creates a deep copy of from
, transmogrified to use the scalar type selected by a template parameter.
The result is never nullptr.
std::exception | if from does not support the destination type. |
Usage:
U | The destination scalar type. For a list of supported types, see the default scalars. |
S | The specific System pointer type to return. |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
std::unique_ptr<System<U> > ToScalarTypeMaybe | ( | ) | const |
Creates a deep copy of this system exactly like ToScalarType(), but returns nullptr if this System does not support the destination type, instead of throwing an exception.
U | The destination scalar type. For a list of supported types, see the default scalars. |
std::unique_ptr<System<symbolic::Expression> > ToSymbolic | ( | ) | const |
Creates a deep copy of this System, transmogrified to use the symbolic scalar type.
The result is never nullptr.
std::exception | if this System does not support symbolic |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
|
static |
Creates a deep copy of from
, transmogrified to use the symbolic scalar type.
The result is never nullptr.
std::exception | if from does not support symbolic |
Usage:
S | The specific System pointer type to return. |
See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.
std::unique_ptr<System<symbolic::Expression> > ToSymbolicMaybe | ( | ) | const |
Creates a deep copy of this system exactly like ToSymbolic(), but returns nullptr if this System does not support symbolic, instead of throwing an exception.
|
static |
Returns a ticket indicating dependence on velocity state variables v.
This does not also indicate a dependence on configuration variables q – you must list that explicitly or use kinematics_ticket() instead. There is no ticket representing just one of the state variables vᵢ.
|
static |
Returns a ticket indicating dependence on all of the abstract state variables in the current Context.
|
static |
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z.
|
static |
Returns a ticket for the cache entry that holds time derivatives of the continuous variables.
|
static |
Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group.
|
static |
Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z.
There is no ticket representing just one of the state variables zᵢ.
|
friend |