Drake
System< T > Class Template Referenceabstract

A superclass template for systems that receive input, maintain state, and produce output of a given mathematical type T. More...

#include <drake/systems/framework/input_port_descriptor.h>

Inheritance diagram for System< T >:
[legend]

Public Member Functions

virtual ~System ()
 
void GetWitnessFunctions (const Context< T > &context, std::vector< const WitnessFunction< T > * > *w) const
 Gets the witness functions active at the beginning of a continuous time interval. More...
 
EvaluateWitness (const Context< T > &context, const WitnessFunction< T > &witness_func) const
 Evaluates a witness function at the given context. More...
 
virtual void AddTriggeredWitnessFunctionToCompositeEventCollection (const WitnessFunction< T > &witness_func, CompositeEventCollection< T > *events) const =0
 Add witness_func to events. More...
 
std::string GetSystemIdString () const
 Returns a string suitable for identifying this particular System in error messages, when it is a subsystem of a larger Diagram. More...
 
Does not allow copy, move, or assignment
 System (const System &)=delete
 
Systemoperator= (const System &)=delete
 
 System (System &&)=delete
 
Systemoperator= (System &&)=delete
 
Resource allocation and initialization

These methods are used to allocate and initialize Context resources.

virtual std::unique_ptr< Context< T > > AllocateContext () const =0
 Allocates a context, initialized with the correct numbers of concrete input ports and state variables for this System. More...
 
virtual std::unique_ptr< CompositeEventCollection< T > > AllocateCompositeEventCollection () const =0
 Allocates a CompositeEventCollection for this system. More...
 
std::unique_ptr< BasicVector< T > > AllocateInputVector (const InputPortDescriptor< T > &descriptor) const
 Given a port descriptor, allocates the vector storage. More...
 
std::unique_ptr< AbstractValueAllocateInputAbstract (const InputPortDescriptor< T > &descriptor) const
 Given a port descriptor, allocates the abstract storage. More...
 
virtual std::unique_ptr< SystemOutput< T > > AllocateOutput (const Context< T > &context) const =0
 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
 Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext. More...
 
virtual std::unique_ptr< DiscreteValues< T > > AllocateDiscreteVariables () const
 Returns a DiscreteState 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 SetDefaults(). More...
 
virtual void SetDefaultState (const Context< T > &context, State< T > *state) const =0
 Assigns default values to all elements of the state. More...
 
virtual void SetDefaults (Context< T > *context) const =0
 
void AllocateFreestandingInputs (Context< T > *context) const
 For each input port, allocates a freestanding input of the concrete type that this System requires, and binds it to the port, disconnecting any prior input. More...
 
virtual std::multimap< int, intGetDirectFeedthroughs () const =0
 Reports all direct feedthroughs from input ports to output ports. 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...
 
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.

void 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 Publish (const Context< T > &context) const
 Forces a publish on the system, given a context. 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 Eval methods in this group return a reference to the already-computed result in the given Context's cache. If the current value is out of date, they first update the cache entry using the corresponding Calc method from the "Calculations" group. Evaluations of input ports instead delegate to the containing Diagram, which arranges to have the appropriate subsystem evaluate the source output port.

const T & EvalConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the conservative power. More...
 
const T & EvalNonConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the non-conservative power. More...
 
template<template< typename > class Vec = BasicVector>
const Vec< T > * EvalVectorInput (const Context< T > &context, int port_index) const
 Causes the vector-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary. More...
 
Eigen::VectorBlock< const VectorX< T > > EvalEigenVectorInput (const Context< T > &context, int port_index) const
 Causes the vector-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary. More...
 
const AbstractValueEvalAbstractInput (const Context< T > &context, int port_index) const
 Causes the abstract-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary. More...
 
template<typename V >
const V * EvalInputValue (const Context< T > &context, int port_index) const
 Causes the abstract-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary. More...
 
Constraint-related functions.
int get_num_constraint_equations (const Context< T > &context) const
 Gets the number of constraint equations for this system using the given context (useful in case the number of constraints is dependent upon the current state (as might be the case with a system modeled using piecewise differential algebraic equations). More...
 
Eigen::VectorXd EvalConstraintEquations (const Context< T > &context) const
 Evaluates the constraint equations for the system at the generalized coordinates and generalized velocity specified by the context. More...
 
Eigen::VectorXd EvalConstraintEquationsDot (const Context< T > &context) const
 Computes the time derivative of each constraint equation, evaluated at the generalized coordinates and generalized velocity specified by the context. More...
 
Eigen::VectorXd CalcVelocityChangeFromConstraintImpulses (const Context< T > &context, const Eigen::MatrixXd &J, const Eigen::VectorXd &lambda) const
 Computes the change in velocity from applying the given constraint forces to the system at the given context. More...
 
double CalcConstraintErrorNorm (const Context< T > &context, const Eigen::VectorXd &error) const
 Computes the norm on constraint error (used as a metric for comparing errors between the outputs of algebraic equations applied to two different state variable instances). More...
 
Calculations

A Drake System defines a set of common computations that are understood by the framework.

Most of these are embodied in a Calc method that unconditionally performs the calculation into an output argument of the appropriate type, using only values from the given Context. These are paired with an Eval method that returns a reference to an already-calculated result residing in the cache; if needed that result is first obtained using the Calc method. See the "Evaluations" group for more information.

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 xcdot of the continuous state xc. More...
 
void CalcDiscreteVariableUpdates (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 CalcDiscreteVariableUpdates (const Context< T > &context, DiscreteValues< T > *discrete_state) const
 This method forces a discrete update on the system given a context, and the updated discrete state is stored in discrete_state. More...
 
void 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 CalcUnrestrictedUpdate (const Context< T > &context, State< T > *state) const
 This method forces an unrestricted update on the system given a context, and the updated state is stored in discrete_state. More...
 
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 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 StepTo() at the point before Simulator integrates continuous state. 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...
 
CalcPotentialEnergy (const Context< T > &context) const
 Calculates and returns the potential energy current stored in the configuration provided in context. More...
 
CalcKineticEnergy (const Context< T > &context) const
 Calculates and returns the kinetic energy currently present in the motion provided in the given Context. More...
 
CalcConservativePower (const Context< T > &context) const
 Calculates and returns the rate at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context. More...
 
CalcNonConservativePower (const Context< T > &context) const
 Calculates and returns the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy (in 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...
 
Utility methods
void set_name (const std::string &name)
 Sets the name of the system. More...
 
std::string get_name () const
 Returns the name last supplied to set_name(), or empty if set_name() was never called. More...
 
std::string GetMemoryObjectName () const
 Returns a name for this System based on a stringification of its type name and memory address. More...
 
void GetPath (std::stringstream *output) const
 Writes the full path of this System in the tree of Systems to output. More...
 
std::string GetPath () const
 
int get_num_input_ports () const
 Returns the number of input ports of the system. More...
 
int get_num_output_ports () const
 Returns the number of output ports of the system. More...
 
const InputPortDescriptor< T > & get_input_port (int port_index) const
 Returns the descriptor of the input port at index port_index. More...
 
const OutputPort< T > & get_output_port (int port_index) const
 Returns the output port at index port_index. More...
 
int get_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...
 
int get_num_total_inputs () const
 Returns the total dimension of all of the input ports (as if they were muxed). More...
 
int get_num_total_outputs () const
 Returns the total dimension of all of the output ports (as if they were muxed). More...
 
void CheckValidOutput (const SystemOutput< T > *output) const
 Checks that output is consistent with the number and size of output ports declared by the system. More...
 
template<typename T1 = T>
void CheckValidContext (const Context< T1 > &context) const
 Checks that context is consistent for this System template. More...
 
VectorX< T > CopyContinuousStateVector (const Context< T > &context) const
 Returns a copy of the continuous state vector xc into an Eigen vector. More...
 
void set_parent (const detail::InputPortEvaluatorInterface< T > *parent)
 Declares that parent is the immediately enclosing Diagram. More...
 
Graphviz methods
std::string GetGraphvizString () const
 Returns a Graphviz string describing this System. More...
 
virtual void GetGraphvizFragment (std::stringstream *dot) const
 Appends a Graphviz fragment to the dot stream. More...
 
virtual void GetGraphvizInputPortToken (const InputPortDescriptor< T > &port, std::stringstream *dot) const
 Appends a fragment to the dot stream identifying the graphviz node representing port. More...
 
virtual void GetGraphvizOutputPortToken (const OutputPort< T > &port, std::stringstream *dot) const
 Appends a fragment to the dot stream identifying the graphviz node representing port. More...
 
int64_t GetGraphvizId () const
 Returns an opaque integer that uniquely identifies this system in the Graphviz output. More...
 
Transmogrification 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 SystemScalarConverterget_system_scalar_converter () const
 (Advanced) Returns the SystemScalarConverter for this object. More...
 

Protected Member Functions

virtual T DoEvaluateWitness (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 at the beginning of a continuous time interval. More...
 
SystemConstraintIndex AddConstraint (std::unique_ptr< SystemConstraint< T >> constraint)
 Adds an already-created constraint to the list of constraints for this System. More...
 
const EventCollection< PublishEvent< T > > & get_forced_publish_events () const
 
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)
 
Event handler dispatch mechanism

For a LeafSystem (or user implemented equivalent classes), these functions need to call the appropriate LeafSystem::DoX event handler.

E.g. LeafSystem::DispatchPublishHandler() calls LeafSystem::DoPublish(). User supplied custom event callbacks embedded in each individual event need to be further dispatched in the LeafSystem::DoX handlers if desired. 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)
     -> leaf_sys.DoPublish(context, event_collection.get_events())
        -> 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.

For a Diagram (or user implemented equivalent classes), these functions must iterate through all subsystems, extract their corresponding subcontext and subevent collections from context and events, and pass those to the subsystems' public non-virtual event handlers if the subevent collection is nonempty (e.g. System::Publish() for publish events).

All of these functions are only called from their corresponding public non-virtual event dispatchers, where context is error checked. The derived implementations can assume that context is valid. See, e.g., LeafSystem::DispatchPublishHandler() and Diagram::DispatchPublishHandler() for more details.

virtual void DispatchPublishHandler (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const =0
 This function dispatches all publish events to the appropriate handlers. More...
 
virtual void DispatchDiscreteVariableUpdateHandler (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const =0
 This function dispatches all discrete update events to the appropriate handlers. More...
 
virtual void DispatchUnrestrictedUpdateHandler (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const =0
 This function dispatches all unrestricted update events to the appropriate handlers. 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, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter. More...
 
const InputPortDescriptor< T > & DeclareInputPort (PortDataType type, int size, optional< RandomDistribution > random_type=nullopt)
 Adds a port with the specified type and size to the input topology. More...
 
const InputPortDescriptor< T > & DeclareAbstractInputPort ()
 Adds an abstract-valued port to the input topology. More...
 
void CreateOutputPort (std::unique_ptr< OutputPort< T >> port)
 Adds an already-created output port to this System. More...
 
Virtual methods for input allocation

Authors of derived Systems should override these methods to self-describe acceptable inputs to the System.

virtual BasicVector< T > * DoAllocateInputVector (const InputPortDescriptor< T > &descriptor) const =0
 Allocates an input vector of the leaf type that the System requires on the port specified by descriptor. More...
 
virtual AbstractValueDoAllocateInputAbstract (const InputPortDescriptor< T > &descriptor) const =0
 Allocates an abstract input of the leaf type that the System requires on the port specified by descriptor. More...
 
Virtual methods for calculations

These virtuals allow concrete systems to implement the calculations defined by the Calc methods in the public interface.

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 Do removed. The public method performs error checking on the arguments so you do not need to do so in your implementation. Users cannot invoke these directly since they are protected. You should place your overrides in the protected or private sections of your concrete class.

virtual void DoCalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const
 Override this if you have any continuous state variables xc in your concrete System to calculate their time derivatives. 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 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 T DoCalcPotentialEnergy (const Context< T > &context) const
 Override this method for physical systems to calculate the potential energy 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 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 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 at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy (in the given Context). 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...
 
virtual std::unique_ptr< System< AutoDiffXd > > DoToAutoDiffXd () const
 NVI implementation of ToAutoDiffXdMaybe. More...
 
virtual std::unique_ptr< System< symbolic::Expression > > DoToSymbolic () const
 NVI implementation of ToSymbolicMaybe. More...
 
Constraint-related functions (protected).
virtual int do_get_num_constraint_equations (const Context< T > &context) const
 Gets the number of constraint equations for this system from the given context. More...
 
virtual Eigen::VectorXd DoEvalConstraintEquations (const Context< T > &context) const
 Evaluates the constraint equations for the system at the generalized coordinates and generalized velocity specified by the context. More...
 
virtual Eigen::VectorXd DoEvalConstraintEquationsDot (const Context< T > &context) const
 Computes the time derivative of each constraint equation, evaluated at the generalized coordinates and generalized velocity specified by the context. More...
 
virtual Eigen::VectorXd DoCalcVelocityChangeFromConstraintImpulses (const Context< T > &context, const Eigen::MatrixXd &J, const Eigen::VectorXd &lambda) const
 Computes the change in velocity from applying the given constraint forces to the system at the given context. More...
 
virtual double DoCalcConstraintErrorNorm (const Context< T > &context, const Eigen::VectorXd &error) const
 Computes the norm of the constraint error. 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...
 
void EvalInputPort (const Context< T > &context, int port_index) const
 Causes an InputPortValue in the context to become up-to-date, delegating to the parent Diagram if necessary. More...
 

Automatic differentiation

From a System templatized by double, you can obtain an identical system templatized by an automatic differentation scalar providing machine-precision computation of partial derivatives of any numerical result of the System with respect to any of the numerical values that can be contained in a Context (time, inputs, parameters, and state).

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 double, you can obtain an identical system templatized by a symbolic expression scalar.

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

Detailed Description

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

A superclass template for systems that receive input, maintain state, and produce output of a given mathematical type T.

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

Constructor & Destructor Documentation

System ( const System< T > &  )
delete
System ( System< T > &&  )
delete
virtual ~System ( )
inlinevirtual
System ( SystemScalarConverter  converter)
inlineexplicitprotected

Constructs an empty System base class object, 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.

Member Function Documentation

SystemConstraintIndex AddConstraint ( std::unique_ptr< SystemConstraint< T >>  constraint)
inlineprotected

Adds an already-created constraint to the list of constraints for this System.

Ownership of the SystemConstraint is transferred to this system.

virtual void AddTriggeredWitnessFunctionToCompositeEventCollection ( const WitnessFunction< T > &  witness_func,
CompositeEventCollection< T > *  events 
) const
pure virtual

Add witness_func to events.

events cannot be nullptr. events should be allocated with this system's AllocateCompositeEventCollection. The system associated with witness_func has to be either this or a subsystem of this depending on whether this is a LeafSystem or a Diagram.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual std::unique_ptr<CompositeEventCollection<T> > AllocateCompositeEventCollection ( ) const
pure virtual

Allocates a CompositeEventCollection for this system.

The allocated instance is used for registering events; for example, Simulator passes this object to System::CalcNextUpdateTime() to allow the system to register upcoming events.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual std::unique_ptr<Context<T> > AllocateContext ( ) const
pure virtual

Allocates a context, initialized with the correct numbers of concrete input ports and state variables for this System.

Since input port pointers are not owned by the context, they should simply be initialized to nullptr.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< double >, VectorSystem< T >, VectorSystem< double >, and SingleOutputVectorSource< T >.

Here is the caller graph for this function:

virtual std::unique_ptr<DiscreteValues<T> > AllocateDiscreteVariables ( ) const
inlinevirtual

Returns a DiscreteState of the same dimensions as the discrete_state allocated in CreateDefaultContext.

The simulator will provide this state as the output argument to Update. By default, allocates nothing. Systems with discrete state variables should override.

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< double >, and MySpringMassSystem< T >.

Here is the caller graph for this function:

void AllocateFreestandingInputs ( Context< T > *  context) const
inline

For each input port, allocates a freestanding 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 freestanding inputs.

std::unique_ptr<AbstractValue> AllocateInputAbstract ( const InputPortDescriptor< T > &  descriptor) const
inline

Given a port descriptor, allocates the abstract storage.

Subclasses with a abstract input ports must override the NVI implementation of this function, DoAllocateInputAbstract, to return an appropriate AbstractValue. The descriptor must match a port declared via DeclareInputPort.

Here is the caller graph for this function:

std::unique_ptr<BasicVector<T> > AllocateInputVector ( const InputPortDescriptor< T > &  descriptor) const
inline

Given a port descriptor, allocates the vector storage.

The default implementation in this class allocates a BasicVector. Subclasses must override the NVI implementation of this function, DoAllocateInputVector, to return input vector types other than BasicVector. The descriptor must match a port declared via DeclareInputPort.

Here is the caller graph for this function:

virtual std::unique_ptr<SystemOutput<T> > AllocateOutput ( const Context< T > &  context) const
pure virtual

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. A Context is provided as an argument to support some specialized use cases. Most typical System implementations should ignore it.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual std::unique_ptr<ContinuousState<T> > AllocateTimeDerivatives ( ) const
inlinevirtual

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.

By default, allocates no derivatives. Systems with continuous state variables should override.

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

T CalcConservativePower ( const Context< T > &  context) const
inline

Calculates and returns the rate at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context.

This quantity will be positive when potential energy is decreasing. Note that kinetic energy will also be affected by non-conservative forces so we can't say whether it is increasing or decreasing in an absolute sense, only whether the conservative power is increasing or decreasing the kinetic energy. Power is in watts (J/s).Non-physical Systems will return zero.

See also
EvalConservativePower()

Here is the caller graph for this function:

double CalcConstraintErrorNorm ( const Context< T > &  context,
const Eigen::VectorXd &  error 
) const
inline

Computes the norm on constraint error (used as a metric for comparing errors between the outputs of algebraic equations applied to two different state variable instances).

This norm need be neither continuous nor differentiable.

Exceptions
std::logic_errorif the dimension of err is not equivalent to the output of get_num_constraint_equations().
void CalcDiscreteVariableUpdates ( const Context< T > &  context,
const EventCollection< DiscreteUpdateEvent< T >> &  events,
DiscreteValues< T > *  discrete_state 
) const
inline

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.

Here is the caller graph for this function:

void CalcDiscreteVariableUpdates ( const Context< T > &  context,
DiscreteValues< T > *  discrete_state 
) const
inline

This method forces a discrete update on the system given a context, and the updated discrete state is stored in discrete_state.

The discrete update event will have a trigger type of kForced, with no attribute or custom callback.

T CalcKineticEnergy ( const Context< T > &  context) const
inline

Calculates and returns the kinetic energy currently present in the motion provided in the given Context.

Non-physical Systems will return zero.

See also
EvalKineticEnergy()
T CalcNextUpdateTime ( const Context< T > &  context,
CompositeEventCollection< T > *  events 
) const
inline

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 scheduled through mechanisms (e.g. GetPerStepEvents()), and the merged CompositeEventCollection will be passed to all event handling mechanisms.

events cannot be null. events will be cleared on entry.

Here is the caller graph for this function:

T CalcNonConservativePower ( const Context< T > &  context) const
inline

Calculates and returns the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy (in the given Context).

Integrating this quantity yields work W, and the total 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!) This method is meaningful only for physical systems; others return zero.

See also
EvalNonConservativePower()
void CalcOutput ( const Context< T > &  context,
SystemOutput< T > *  outputs 
) const
inline

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.

Here is the caller graph for this function:

T CalcPotentialEnergy ( const Context< T > &  context) const
inline

Calculates and returns the potential energy current stored in the configuration provided in context.

Non-physical Systems will return zero.

See also
EvalPotentialEnergy()
void CalcTimeDerivatives ( const Context< T > &  context,
ContinuousState< T > *  derivatives 
) const
inline

Calculates the time derivatives xcdot of the continuous state xc.

The derivatives vector will correspond elementwise with the continuous state in the given Context. Thus, if the state in the Context has second-order structure xc=[q v z], that same structure applies to the derivatives so we will have xcdot=[qdot vdot zdot].

Parameters
contextThe Context whose time, input port, parameter, and state values are used to evaluate the derivatives.
derivativesThe time derivatives xcdot. Must be the same size as the continuous state vector in context.

Here is the caller graph for this function:

void CalcUnrestrictedUpdate ( const Context< T > &  context,
const EventCollection< UnrestrictedUpdateEvent< T >> &  events,
State< T > *  state 
) const
inline

This method is the public entry point for dispatching all unrestricted update event handlers.

Using all the unrestricted update handers 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.

Exceptions
std::logic_errorif the dimensionality of the state variables changes in the callback.

Here is the caller graph for this function:

void CalcUnrestrictedUpdate ( const Context< T > &  context,
State< T > *  state 
) const
inline

This method forces an unrestricted update on the system given a context, and the updated state is stored in discrete_state.

The unrestricted update event will have a trigger type of kForced, with no additional data, attribute or custom callback.

See also
CalcUnrestrictedUpdate(const Context<T>&, const EventCollection<UnrestrictedUpdateEvent<T>>*, State<T>* state) for more information.
Eigen::VectorXd CalcVelocityChangeFromConstraintImpulses ( const Context< T > &  context,
const Eigen::MatrixXd &  J,
const Eigen::VectorXd &  lambda 
) const
inline

Computes the change in velocity from applying the given constraint forces to the system at the given context.

Parameters
contextthe current system state, provision of which also yields the ability of the constraints to be dependent upon the current system state (as might be the case with a piecewise differential algebraic equation).
Ja m × n constraint Jacobian matrix of the m constraint equations g() differentiated with respect to the n configuration variables q (i.e., J should be ∂g/∂q). If the time derivatives of the generalized coordinates of the system are not identical to the generalized velocity (in general they need not be, e.g., if generalized coordinates use unit unit quaternions to represent 3D orientation), J should instead be defined as ∂g/∂q⋅N, where N ≡ ∂q/∂ꝗ is the Jacobian matrix (dependent on q) of the generalized coordinates with respect to the quasi-coordinates (ꝗ, pronounced "qbar", where dꝗ/dt are the generalized velocities).
lambdathe vector of constraint forces (of same dimension as the number of rows in the Jacobian matrix, J)
Returns
a n dimensional vector, where n is the dimension of the quasi-coordinates.
void CheckValidContext ( const Context< T1 > &  context) const
inline

Checks that context is consistent for this System template.

Supports any scalar type, but expects T by default.

Exceptions
exceptionunless context is valid for this system.
Template Parameters
T1the scalar type of the Context to check.

Here is the caller graph for this function:

void CheckValidOutput ( const SystemOutput< T > *  output) const
inline

Checks that output is consistent with the number and size of output ports declared by the system.

Exceptions
exceptionunless output is non-null and valid for this system.
VectorX<T> CopyContinuousStateVector ( const Context< T > &  context) const
inline

Returns a copy of the continuous state vector xc into an Eigen vector.

std::unique_ptr<Context<T> > CreateDefaultContext ( ) const
inline

This convenience method allocates a context using AllocateContext() and sets its default values using SetDefaults().

Here is the caller graph for this function:

void CreateOutputPort ( std::unique_ptr< OutputPort< T >>  port)
inlineprotected

Adds an already-created output port to this System.

Insists that the port already contains a reference to this System, and that the port's index is already set to the next available output port index for this System.

const InputPortDescriptor<T>& DeclareAbstractInputPort ( )
inlineprotected

Adds an abstract-valued port to the input topology.

Returns
descriptor of declared port.

Here is the caller graph for this function:

const InputPortDescriptor<T>& DeclareInputPort ( PortDataType  type,
int  size,
optional< RandomDistribution random_type = nullopt 
)
inlineprotected

Adds a port with the specified type and size to the input topology.

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.

Returns
descriptor of declared port.

Here is the caller graph for this function:

virtual void DispatchDiscreteVariableUpdateHandler ( const Context< T > &  context,
const EventCollection< DiscreteUpdateEvent< T >> &  events,
DiscreteValues< T > *  discrete_state 
) const
protectedpure virtual

This function dispatches all discrete update events to the appropriate handlers.

discrete_state cannot be null.

virtual void DispatchPublishHandler ( const Context< T > &  context,
const EventCollection< PublishEvent< T >> &  events 
) const
protectedpure virtual

This function dispatches all publish events to the appropriate handlers.

virtual void DispatchUnrestrictedUpdateHandler ( const Context< T > &  context,
const EventCollection< UnrestrictedUpdateEvent< T >> &  events,
State< T > *  state 
) const
protectedpure virtual

This function dispatches all unrestricted update events to the appropriate handlers.

state cannot be null.

virtual int do_get_num_constraint_equations ( const Context< T > &  context) const
inlineprotectedvirtual

Gets the number of constraint equations for this system from the given context.

The context is supplied in case the number of constraints is dependent upon the current state (as might be the case with a piecewise differential algebraic equation). Derived classes can override this function, which is called by get_num_constraint_equations().

See also
get_num_constraint_equations() for parameter documentation.
Returns
zero by default
virtual AbstractValue* DoAllocateInputAbstract ( const InputPortDescriptor< T > &  descriptor) const
protectedpure virtual

Allocates an abstract input of the leaf type that the System requires on the port specified by descriptor.

Caller owns the returned memory.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

virtual BasicVector<T>* DoAllocateInputVector ( const InputPortDescriptor< T > &  descriptor) const
protectedpure virtual

Allocates an input vector of the leaf type that the System requires on the port specified by descriptor.

Caller owns the returned memory.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

virtual T DoCalcConservativePower ( const Context< T > &  context) const
inlineprotectedvirtual

Override this method to return the rate at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context.

This quantity must be positive when potential energy is decreasing. Power is in watts (J/s).

By default, returns zero. Continuous, physical systems should override. You may assume that context has already been validated before it is passed to you here.

Reimplemented in RigidBodyPlant< T >, RigidBodyPlant< double >, and SpringMassSystem< T >.

virtual double DoCalcConstraintErrorNorm ( const Context< T > &  context,
const Eigen::VectorXd &  error 
) const
inlineprotectedvirtual

Computes the norm of the constraint error.

This default implementation computes a Euclidean norm of the error. Derived classes can override this function, which is called by CalcConstraintErrorNorm(). This norm need be neither continuous nor differentiable.

See also
CalcConstraintErrorNorm() for parameter documentation.
virtual T DoCalcKineticEnergy ( const Context< T > &  context) const
inlineprotectedvirtual

Override this method for physical systems to calculate the kinetic energy 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.

Reimplemented in RigidBodyPlant< T >, RigidBodyPlant< double >, and SpringMassSystem< T >.

virtual void DoCalcNextUpdateTime ( const Context< T > &  context,
CompositeEventCollection< T > *  events,
T *  time 
) const
inlineprotectedvirtual

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.

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< double >, and LcmSubscriberSystem.

virtual T DoCalcNonConservativePower ( const Context< T > &  context) const
inlineprotectedvirtual

Override this method to return the rate at which mechanical energy is being generated (positive) or dissipated (negative) other than by conversion between potential and kinetic energy (in the given Context).

Integrating this quantity yields work W, and the total 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!) This method is meaningful only for physical systems; others return zero.

By default, returns zero. Continuous, physical systems should override. You may assume that context has already been validated before it is passed to you here.

Reimplemented in RigidBodyPlant< T >, RigidBodyPlant< double >, and SpringMassSystem< T >.

virtual T DoCalcPotentialEnergy ( const Context< T > &  context) const
inlineprotectedvirtual

Override this method for physical systems to calculate the potential energy 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.

Reimplemented in RigidBodyPlant< T >, RigidBodyPlant< double >, and SpringMassSystem< T >.

virtual void DoCalcTimeDerivatives ( const Context< T > &  context,
ContinuousState< T > *  derivatives 
) const
inlineprotectedvirtual

Override this if you have any continuous state variables xc 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 xc=[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 Diagram< T >, Diagram< double >, RigidBodyPlant< T >, RigidBodyPlant< double >, SpringMassSystem< T >, PidController< T >, VectorSystem< T >, VectorSystem< double >, SpringMassDamperSystem< T >, StiffDoubleMassSpringSystem< T >, TimeVaryingAffineSystem< T >, DiscontinuousSpringMassDamperSystem< T >, and RobertsonSystem< T >.

virtual Eigen::VectorXd DoCalcVelocityChangeFromConstraintImpulses ( const Context< T > &  context,
const Eigen::MatrixXd &  J,
const Eigen::VectorXd &  lambda 
) const
inlineprotectedvirtual

Computes the change in velocity from applying the given constraint forces to the system at the given context.

Derived classes can override this function, which is called by CalcVelocityChangeFromConstraintImpulses().

Returns
the zero vector of dimension of the dimension of the quasi-coordinates, by default.
See also
CalcVelocityChangeFromConstraintImpulses() for parameter documentation.
virtual Eigen::VectorXd DoEvalConstraintEquations ( const Context< T > &  context) const
inlineprotectedvirtual

Evaluates the constraint equations for the system at the generalized coordinates and generalized velocity specified by the context.

The context allows the set of constraints to be dependent upon the current system state (as might be the case with a piecewise differential algebraic equation). The default implementation of this function returns a zero-dimensional vector. Derived classes can override this function, which is called by EvalConstraintEquations().

See also
EvalConstraintEquations() for parameter documentation.
Returns
a vector of dimension get_num_constraint_equations(); the zero vector indicates that the algebraic constraints are all satisfied.
virtual Eigen::VectorXd DoEvalConstraintEquationsDot ( const Context< T > &  context) const
inlineprotectedvirtual

Computes the time derivative of each constraint equation, evaluated at the generalized coordinates and generalized velocity specified by the context.

The context allows the set of constraints to be dependent upon the current system state (as might be the case with a piecewise differential algebraic equation). The default implementation of this function returns a zero-dimensional vector. Derived classes can override this function, which is called by EvalConstraintEquationsDot().

Returns
a vector of dimension get_num_constraint_equations().
See also
EvalConstraintEquationsDot() for parameter documentation.
virtual T DoEvaluateWitness ( const Context< T > &  context,
const WitnessFunction< T > &  witness_func 
) const
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 >, and LeafSystem< double >.

virtual void DoGetPerStepEvents ( const Context< T > &  context,
CompositeEventCollection< T > *  events 
) const
inlineprotectedvirtual

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. An overriding implementation of this method should not clear events, and only append to it. 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.

See also
GetPerStepEvents()
virtual void DoGetWitnessFunctions ( const Context< T > &  ,
std::vector< const WitnessFunction< T > * > *   
) const
inlineprotectedvirtual

Derived classes can override this method to provide witness functions active at the beginning of a continuous time interval.

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

virtual void DoMapQDotToVelocity ( const Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  qdot,
VectorBase< T > *  generalized_velocity 
) const
inlineprotectedvirtual

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::runtime_error 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 >, Diagram< double >, RigidBodyPlant< T >, and RigidBodyPlant< double >.

virtual void DoMapVelocityToQDot ( const Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  generalized_velocity,
VectorBase< T > *  qdot 
) const
inlineprotectedvirtual

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::runtime_error 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 >, Diagram< double >, RigidBodyPlant< T >, and RigidBodyPlant< double >.

virtual std::unique_ptr<System<AutoDiffXd> > DoToAutoDiffXd ( ) const
inlineprotectedvirtual

NVI implementation of ToAutoDiffXdMaybe.

Returns
nullptr if this System does not support autodiff

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual std::unique_ptr<System<symbolic::Expression> > DoToSymbolic ( ) const
inlineprotectedvirtual

NVI implementation of ToSymbolicMaybe.

Returns
nullptr if this System does not support symbolic form

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

const AbstractValue* EvalAbstractInput ( const Context< T > &  context,
int  port_index 
) const
inline

Causes the abstract-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary.

Returns the port's abstract value pointer, or nullptr if the port is not connected.

Here is the caller graph for this function:

const T& EvalConservativePower ( const Context< T > &  context) const
inline

Returns a reference to the cached value of the conservative power.

If necessary the cache will be updated first using CalcConservativePower().

See also
CalcConservativePower()
Eigen::VectorXd EvalConstraintEquations ( const Context< T > &  context) const
inline

Evaluates the constraint equations for the system at the generalized coordinates and generalized velocity specified by the context.

The context allows the set of constraints to be dependent upon the current system state (as might be the case with a system modeled using piecewise differential algebraic equations).

Returns
a vector of dimension get_num_constraint_equations(); the zero vector indicates that the algebraic constraints are all satisfied.
Eigen::VectorXd EvalConstraintEquationsDot ( const Context< T > &  context) const
inline

Computes the time derivative of each constraint equation, evaluated at the generalized coordinates and generalized velocity specified by the context.

The context allows the set of constraints to be dependent upon the current system state (as might be the case with a system modeled using piecewise differential algebraic equations).

Returns
a vector of dimension get_num_constraint_equations().
Eigen::VectorBlock<const VectorX<T> > EvalEigenVectorInput ( const Context< T > &  context,
int  port_index 
) const
inline

Causes the vector-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary.

Returns the port's value as an Eigen expression.

Here is the caller graph for this function:

void EvalInputPort ( const Context< T > &  context,
int  port_index 
) const
inlineprotected

Causes an InputPortValue in the context to become up-to-date, delegating to the parent Diagram if necessary.

This is a framework implementation detail. User code should never call it.

const V* EvalInputValue ( const Context< T > &  context,
int  port_index 
) const
inline

Causes the abstract-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary.

Returns the port's abstract value, or nullptr if the port is not connected.

Template Parameters
VThe type of data expected.
const T& EvalNonConservativePower ( const Context< T > &  context) const
inline

Returns a reference to the cached value of the non-conservative power.

If necessary the cache will be updated first using CalcNonConservativePower().

See also
CalcNonConservativePower()
T EvaluateWitness ( const Context< T > &  context,
const WitnessFunction< T > &  witness_func 
) const
inline

Evaluates a witness function at the given context.

Here is the caller graph for this function:

const Vec<T>* EvalVectorInput ( const Context< T > &  context,
int  port_index 
) const
inline

Causes the vector-valued input port with the given port_index to become up-to-date, delegating to our parent Diagram if necessary.

Returns the port's value, or nullptr if the port is not connected.

Throws std::bad_cast if the port is not vector-valued. Returns nullptr if the port is vector valued, but not of type Vec. Aborts if the port does not exist.

Template Parameters
VecThe template type of the input vector, which must be a subclass of BasicVector.

Here is the caller graph for this function:

void FixInputPortsFrom ( const System< double > &  other_system,
const Context< double > &  other_context,
Context< T > *  target_context 
) const
inline

Fixes all of the input ports in target_context to their current values in other_context, as evaluated by other_system.

Throws an exception unless other_context and target_context both have the same shape as this System, and the other_system. Ignores disconnected inputs.

const SystemConstraint<T>& get_constraint ( SystemConstraintIndex  constraint_index) const
inline

Returns the constraint at index constraint_index.

Exceptions
std::out_of_rangefor an invalid constraint_index.

Here is the caller graph for this function:

const EventCollection<DiscreteUpdateEvent<T> >& get_forced_discrete_update_events ( ) const
inlineprotected
const EventCollection<PublishEvent<T> >& get_forced_publish_events ( ) const
inlineprotected
const EventCollection<UnrestrictedUpdateEvent<T> >& get_forced_unrestricted_update_events ( ) const
inlineprotected
const InputPortDescriptor<T>& get_input_port ( int  port_index) const
inline

Returns the descriptor of the input port at index port_index.

Here is the caller graph for this function:

std::string get_name ( ) const
inline

Returns the name last supplied to set_name(), or empty if set_name() was never called.

Systems created through transmogrification have by default an identical name to the system they were created from.

Here is the caller graph for this function:

int get_num_constraint_equations ( const Context< T > &  context) const
inline

Gets the number of constraint equations for this system using the given context (useful in case the number of constraints is dependent upon the current state (as might be the case with a system modeled using piecewise differential algebraic equations).

int get_num_constraints ( ) const
inline

Returns the number of constraints specified for the system.

Here is the caller graph for this function:

int get_num_input_ports ( ) const
inline

Returns the number of input ports of the system.

Here is the caller graph for this function:

int get_num_output_ports ( ) const
inline

Returns the number of output ports of the system.

Here is the caller graph for this function:

int get_num_total_inputs ( ) const
inline

Returns the total dimension of all of the input ports (as if they were muxed).

int get_num_total_outputs ( ) const
inline

Returns the total dimension of all of the output ports (as if they were muxed).

const OutputPort<T>& get_output_port ( int  port_index) const
inline

Returns the output port at index port_index.

Here is the caller graph for this function:

const SystemScalarConverter& get_system_scalar_converter ( ) const
inline

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

virtual std::multimap<int, int> GetDirectFeedthroughs ( ) const
pure virtual

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

  • 0 ≤ u < m,
  • 0 ≤ v < n,
  • and there might be a direct feedthrough from input iᵤ to each output oᵥ.

Implemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual void GetGraphvizFragment ( std::stringstream *  dot) const
inlinevirtual

Appends a Graphviz fragment to the dot stream.

The fragment must be valid Graphviz when wrapped in a digraph or subgraph stanza. Does nothing by default.

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, LeafSystem< double >, and PidController< T >.

int64_t GetGraphvizId ( ) const
inline

Returns an opaque integer that uniquely identifies this system in the Graphviz output.

Here is the caller graph for this function:

virtual void GetGraphvizInputPortToken ( const InputPortDescriptor< T > &  port,
std::stringstream *  dot 
) const
inlinevirtual

Appends a fragment to the dot stream identifying the graphviz node representing port.

Does nothing by default.

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

virtual void GetGraphvizOutputPortToken ( const OutputPort< T > &  port,
std::stringstream *  dot 
) const
inlinevirtual

Appends a fragment to the dot stream identifying the graphviz node representing port.

Does nothing by default.

Reimplemented in Diagram< T >, Diagram< double >, LeafSystem< T >, and LeafSystem< double >.

Here is the caller graph for this function:

std::string GetGraphvizString ( ) const
inline

Returns a Graphviz string describing this System.

To render the string, use the Graphviz tool, dot. http://www.graphviz.org/Documentation/dotguide.pdf

std::string GetMemoryObjectName ( ) const
inline

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.

Eigen::VectorBlock<VectorX<T> > GetMutableOutputVector ( SystemOutput< T > *  output,
int  port_index 
) const
inlineprotected

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.

void GetPath ( std::stringstream *  output) const
inline

Writes the full path of this System in the tree of Systems to output.

The path has the form (::ancestor_system_name)*::this_system_name.

Here is the caller graph for this function:

std::string GetPath ( ) const
inline

Here is the caller graph for this function:

void GetPerStepEvents ( const Context< T > &  context,
CompositeEventCollection< T > *  events 
) const
inline

This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in StepTo() 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 other CompositeEventCollection instances generated 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.

std::string GetSystemIdString ( ) const
inline

Returns a string suitable for identifying this particular System in error messages, when it is a subsystem of a larger Diagram.

This method captures human-readable subsystem identification best practice; the specifics of that are likely to change over time. However it will always be formatted like "System xxx" or "adjective System xxx" so that the remainder of the error message will continue to make sense. Currently it returns "system_type_name System subsystem_pathname".

void GetWitnessFunctions ( const Context< T > &  context,
std::vector< const WitnessFunction< T > * > *  w 
) const
inline

Gets the witness functions active at the beginning of a continuous time interval.

DoGetWitnessFunctions() does the actual work.

Parameters
contexta valid context for the System (aborts if not true).
[out]wa valid pointer to an empty vector that will store pointers to the witness functions active at the beginning of the continuous time interval. The method aborts if witnesses is null or non-empty.

Here is the caller graph for this function:

bool HasAnyDirectFeedthrough ( ) const
inline

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
inline

Returns true if there might be direct-feedthrough from any input port to the given output_port, and false otherwise.

Here is the caller graph for this function:

bool HasDirectFeedthrough ( int  input_port,
int  output_port 
) const
inline

Returns true if there might be direct-feedthrough from the given input_port to the given output_port, and false otherwise.

void MapQDotToVelocity ( const Context< T > &  context,
const VectorBase< T > &  qdot,
VectorBase< T > *  generalized_velocity 
) const
inline

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.

See also
MapVelocityToQDot()
void MapQDotToVelocity ( const Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  qdot,
VectorBase< T > *  generalized_velocity 
) const
inline

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
inline

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.

See also
MapQDotToVelocity()
void MapVelocityToQDot ( const Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  generalized_velocity,
VectorBase< T > *  qdot 
) const
inline

Transforms the given generalized velocity to the time derivative of generalized configuration.

See the other signature of MapVelocityToQDot() for more information.

System& operator= ( System< T > &&  )
delete
System& operator= ( const System< T > &  )
delete
void Publish ( const Context< T > &  context,
const EventCollection< PublishEvent< T >> &  events 
) const
inline

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, which is typically the publish portion of the heterogeneous event collection generated by CalcNextUpdateTime or GetPerStepEvents.

Note
When publishing is scheduled at particular times, those times likely will not coincide with integrator step times. A Simulator may interpolate to generate a suitable Context, or it may adjust the integrator step size so that a step begins exactly at the next publication time. In the latter case the change in step size may affect the numerical result somewhat since a smaller integrator step produces a more accurate solution.

Here is the caller graph for this function:

void Publish ( const Context< T > &  context) const
inline

Forces a publish on the system, given a context.

The publish event will have a trigger type of kForced, with no additional data, attribute or custom callback. 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.

void set_forced_discrete_update_events ( std::unique_ptr< EventCollection< DiscreteUpdateEvent< T >>>  forced)
inlineprotected
void set_forced_publish_events ( std::unique_ptr< EventCollection< PublishEvent< T >>>  forced)
inlineprotected
void set_forced_unrestricted_update_events ( std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T >>>  forced)
inlineprotected
void set_name ( const std::string &  name)
inline

Sets the name of the system.

It is recommended that the name not include the character ':', since the path delimiter is "::". When creating a Diagram, names of sibling subsystems should be unique.

Here is the caller graph for this function:

void set_parent ( const detail::InputPortEvaluatorInterface< T > *  parent)
inline

Declares that parent is the immediately enclosing Diagram.

The enclosing Diagram is needed to evaluate inputs recursively. Aborts if the parent has already been set to something else.

This is a dangerous implementation detail. Conceptually, a System ought to be completely ignorant of its parent Diagram. However, we need this pointer so that we can cause our inputs to be evaluated. See https://github.com/RobotLocomotion/drake/pull/3455.

virtual void SetDefaults ( Context< T > *  context) const
pure virtual
virtual void SetDefaultState ( const Context< T > &  context,
State< T > *  state 
) const
pure virtual

Assigns default values to all elements of the state.

Overrides must not change the number of state variables.

Implemented in Diagram< T >, Diagram< double >, RigidBodyPlant< T >, RigidBodyPlant< double >, LcmSubscriberSystem, LeafSystem< T >, LeafSystem< double >, StiffDoubleMassSpringSystem< T >, RobotPlanInterpolator, and PickAndPlaceStateMachineSystem.

std::unique_ptr<System<AutoDiffXd> > ToAutoDiffXd ( ) const
inline

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.

Exceptions
exceptionif this System does not support autodiff

See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.

Here is the caller graph for this function:

static std::unique_ptr<S<AutoDiffXd> > ToAutoDiffXd ( const S< T > &  from)
inlinestatic

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.

Exceptions
exceptionif from does not support autodiff

Usage:

MySystem<double> plant;
std::unique_ptr<MySystem<AutoDiffXd>> ad_plant =
Template Parameters
SThe 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
inline

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.

Here is the caller graph for this function:

std::unique_ptr<System<symbolic::Expression> > ToSymbolic ( ) const
inline

Creates a deep copy of this System, transmogrified to use the symbolic scalar type.

The result is never nullptr.

Exceptions
exceptionif this System does not support symbolic

See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.

Here is the caller graph for this function:

static std::unique_ptr<S<symbolic::Expression> > ToSymbolic ( const S< T > &  from)
inlinestatic

Creates a deep copy of from, transmogrified to use the symbolic scalar type.

The result is never nullptr.

Exceptions
exceptionif this System does not support symbolic

Usage:

MySystem<double> plant;
std::unique_ptr<MySystem<symbolic::Expression>> sym_plant =
Template Parameters
SThe 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
inline

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.

Here is the caller graph for this function:


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