Drake
SystemBase Class Referenceabstract

Provides non-templatized functionality shared by the templatized System classes. More...

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

Inheritance diagram for SystemBase:
[legend]
Collaboration diagram for SystemBase:
[legend]

Public Member Functions

 ~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...
 
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...
 
void ThrowIfContextNotCompatible (const ContextBase &context) const final
 Throws an exception with an appropriate message if the given context is not compatible with this System. More...
 
std::unique_ptr< ContextBaseAllocateContext () const
 Returns a Context suitable for use with this System. More...
 
int get_num_input_ports () const
 Returns the number of input ports currently allocated in this System. More...
 
int get_num_output_ports () const
 Returns the number of output ports currently allocated in this System. More...
 
const InputPortBaseget_input_port_base (InputPortIndex port_index) const
 Returns a reference to an InputPort given its port_index. More...
 
const OutputPortBaseget_output_port_base (OutputPortIndex port_index) const
 Returns a reference to an OutputPort given its port_index. More...
 
int get_num_total_inputs () const
 Returns the total dimension of all of the vector-valued input ports (as if they were muxed). More...
 
int get_num_total_outputs () const
 Returns the total dimension of all of the vector-valued output ports (as if they were muxed). More...
 
int num_cache_entries () const
 Returns the number nc of cache entries currently allocated in this System. More...
 
const CacheEntryget_cache_entry (CacheIndex index) const
 Return a reference to a CacheEntry given its index. More...
 
void CheckValidContext (const ContextBase &context) const
 Checks whether the given context is valid for this System and throws an exception with a helpful message if not. More...
 
Does not allow copy, move, or assignment
 SystemBase (const SystemBase &)=delete
 
SystemBaseoperator= (const SystemBase &)=delete
 
 SystemBase (SystemBase &&)=delete
 
SystemBaseoperator= (SystemBase &&)=delete
 
Input port evaluation

These methods provide scalar type-independent evaluation of a System input port in a particular Context.

If necessary, they first cause the port's value to become up to date, then they return a reference to the now-up-to-date value in the given Context.

Specified preconditions for these methods 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.

See also
System::EvalVectorInput(), System::EvalEigenVectorInput() for scalar type-specific input port access.
const AbstractValueEvalAbstractInput (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...
 
Declare cache entries

Methods in this section are used by derived classes to declare cache entries for their own internal computations. (Other cache entries are provided automatically for well-known computations such as output ports and time derivatives.) Cache entries may contain values of any type, however the type for any particular cache entry is fixed after first allocation. Every cache entry must have an allocator function Alloc() and a calculator function Calc(). Alloc() returns an object suitable for holding a value of the cache entry. Calc() uses the contents of a given Context to produce the cache entry's value, which is placed in an object of the type returned by Alloc().

Prerequisites

Correct runtime caching behavior depends critically on understanding the dependencies of the cache entry's Calc() function (we call those "prerequisites"). If none of the prerequisites has changed since the last time Calc() was invoked to set the cache entry's value, then we don't need to perform a potentially expensive recalculation. On the other hand, if any of the prerequisites has changed then the current value is invalid and must not be used without first recomputing.

Currently it is not possible for Drake to infer prerequisites accurately and automatically from inspection of the Calc() implementation. Therefore, if you don't say otherwise, Drake will assume Calc() is dependent on all value sources in the Context, including time, state, input ports, parameters, and accuracy. That means the cache entry's value will be considered invalid if any of those sources has changed since the last time the value was calculated. That is safe, but can result in more computation than necessary. If you know that your Calc() method has fewer prerequisites, you may say so by providing an explicit list in the prerequisites_of_calc parameter. Every possible prerequisite has a DependencyTicket ("ticket"), and the list should consist of tickets. For example, if your calculator depends only on time (e.g. Calc(context) is sin(context.get_time())) then you would specify prerequisites_of_calc={time_ticket()} here. See Dependency tickets for a list of the possible tickets and what they mean.

Warning
It is critical that the prerequisite list you supply be accurate, or at least conservative, for correct functioning of the caching system. Drake cannot currently detect that a Calc() function accesses an undeclared prerequisite. Even assuming you have correctly listed the prerequisites, you should include a prominent comment in every Calc() implementation noting that if the implementation is changed then the prerequisite list must be updated correspondingly.

A technique you can use to ensure that prerequisites have been properly specified is to make use of the Context's DisableCaching() method, which causes cache values to be recalculated unconditionally. You should get identical results with caching enabled or disabled, with speed being the only difference.

See also
drake::systems::ContextBase::DisableCaching()

Which signature to use?

Although the allocator and calculator functions ultimately satisfy generic function signatures defined in CacheEntry, we provide a variety of DeclareCacheEntry() signatures here for convenient specification, with mapping to the generic form handled invisibly. In particular, allocators are most easily defined by providing a model value that can be used to construct an allocator that copies the model when a new value object is needed. Alternatively a method can be provided that constructs a value object when invoked (those methods are conventionally, but not necessarily, named MakeSomething() where Something is replaced by the cache entry value type).

Because cache entry values are ultimately stored in AbstractValue objects, the underlying types must be suitable. That means the type must be copy constructible or cloneable. For methods below that are not given an explicit model value or construction ("make") method, the underlying type must also be default constructible.

See also
drake::systems::Value for more about abstract values.
const CacheEntryDeclareCacheEntry (std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 Declares a new CacheEntry in this System using the least-restrictive definitions for the associated functions. More...
 
template<class MySystem , class MyContext , typename ValueType >
const CacheEntryDeclareCacheEntry (std::string description, ValueType(MySystem::*make)() const, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 Declares a cache entry by specifying member functions to use both for the allocator and calculator. More...
 
template<class MySystem , class MyContext , typename ValueType >
const CacheEntryDeclareCacheEntry (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 >
const CacheEntryDeclareCacheEntry (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...
 

Protected Member Functions

 SystemBase ()=default
 (Internal use only) Default constructor. 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...
 
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...
 
const CacheEntryDeclareCacheEntryWithKnownTicket (DependencyTicket known_ticket, std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, 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 AbstractValueEvalAbstractInputImpl (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::out_of_range 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::out_of_range 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::out_of_range 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::logic_error 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::logic_error 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::logic_error because someone called API method func, that requires this input port to be evaluatable, but the port was neither fixed nor connected. More...
 
const InputPortBaseGetInputPortBaseOrThrow (const char *func, int port_index) const
 (Internal use only) Returns the InputPortBase at index port_index, throwing std::out_of_range we don't like the port index. More...
 
const OutputPortBaseGetOutputPortBaseOrThrow (const char *func, int port_index) const
 (Internal use only) Returns the OutputPortBase at index port_index, throwing std::out_of_range we don't like the port index. 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< ContextBaseDoAllocateContext () const =0
 Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method. More...
 
virtual void DoCheckValidContext (const ContextBase &) const =0
 Derived classes must implement this to verify that the supplied Context is suitable, and throw an exception if not. More...
 

Static Protected Member Functions

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

Dependency tickets

Use these tickets to declare well-known sources as prerequisites of a downstream computation such as an output port, derivative, update, or cache entry. The ticket numbers for these sources are the same for all systems. For time and accuracy they refer to the same global resource; otherwise they refer to the specified sources within the referencing system.

A dependency ticket for a more specific resource (a particular input or output port, a discrete variable group, abstract state variable, a parameter, or a cache entry) is allocated and stored with the resource when it is declared. Usually the tickets are obtained directly from the resource but you can recover them with methods here knowing only the resource index.

DependencyTicket input_port_ticket (InputPortIndex index)
 Returns a ticket indicating dependence on the input port indicated by index. More...
 
DependencyTicket output_port_ticket (OutputPortIndex index)
 Returns a ticket indicating dependence on the output port indicated by index. More...
 
DependencyTicket cache_entry_ticket (CacheIndex index)
 Returns a ticket indicating dependence on the cache entry indicated by index. 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_parameters () 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...
 
DependencyTicket discrete_state_ticket (DiscreteStateIndex index) const
 Returns a ticket indicating dependence on a particular discrete state variable (may be a vector). More...
 
DependencyTicket abstract_state_ticket (AbstractStateIndex index) const
 Returns a ticket indicating dependence on a particular abstract state variable. More...
 
DependencyTicket numeric_parameter_ticket (NumericParameterIndex index) const
 Returns a ticket indicating dependence on a particular numeric parameter (may be a vector). More...
 
DependencyTicket abstract_parameter_ticket (AbstractParameterIndex index) const
 Returns a ticket indicating dependence on a particular abstract parameter. More...
 
static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, state, input ports, parameters, and the accuracy setting (but not cache entries). More...
 
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 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 xcdot_ticket ()
 Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More...
 
static DependencyTicket xdhat_ticket ()
 Returns a ticket for the cache entry that holds the discrete state update for the numerical discrete variables in the state. More...
 
static DependencyTicket configuration_ticket ()
 Returns a ticket indicating dependence on all the configuration variables for this System. More...
 
static DependencyTicket velocity_ticket ()
 (Advanced) Returns a ticket indicating dependence on all of the velocity variables, but not the configuration variables for this System. More...
 
static DependencyTicket kinematics_ticket ()
 Returns a ticket indicating dependence on all of the configuration and velocity state variables of this System. 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...
 

Detailed Description

Provides non-templatized functionality shared by the templatized System classes.

Terminology: in general a Drake System is a tree structure composed of "subsystems", which are themselves System objects. The corresponding Context is a parallel tree structure composed of "subcontexts", which are themselves Context objects. There is a one-to-one correspondence between subsystems and subcontexts. Within a given System (Context), its child subsystems (subcontexts) are indexed using a SubsystemIndex; there is no separate SubcontextIndex since the numbering must be identical.

Constructor & Destructor Documentation

SystemBase ( const SystemBase )
delete
SystemBase ( SystemBase &&  )
delete
~SystemBase ( )
override
SystemBase ( )
protecteddefault

(Internal use only) Default constructor.

Here is the caller graph for this function:

Member Function Documentation

DependencyTicket abstract_parameter_ticket ( AbstractParameterIndex  index) const
inline

Returns a ticket indicating dependence on a particular abstract parameter.

Here is the call graph for this function:

DependencyTicket abstract_state_ticket ( AbstractStateIndex  index) const
inline

Returns a ticket indicating dependence on a particular abstract state variable.

static DependencyTicket accuracy_ticket ( )
inlinestatic

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.

void AddAbstractParameter ( AbstractParameterIndex  index)
inlineprotected

(Internal use only) Assigns a ticket to a new abstract parameter with the given index.

Precondition
The supplied index must be the next available one; that is, indexes must be assigned sequentially.

Here is the call graph for this function:

void AddAbstractState ( AbstractStateIndex  index)
inlineprotected

(Internal use only) Assigns a ticket to a new abstract state variable with the given index.

Precondition
The supplied index must be the next available one; that is, indexes must be assigned sequentially.

Here is the call graph for this function:

void AddDiscreteStateGroup ( DiscreteStateIndex  index)
inlineprotected

(Internal use only) Assigns a ticket to a new discrete variable group with the given index.

Precondition
The supplied index must be the next available one; that is, indexes must be assigned sequentially.

Here is the call graph for this function:

void AddInputPort ( std::unique_ptr< InputPortBase port)
inlineprotected

(Internal use only) Adds an already-constructed input 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 input port index for this System.

Here is the call graph for this function:

void AddNumericParameter ( NumericParameterIndex  index)
inlineprotected

(Internal use only) Assigns a ticket to a new numeric parameter with the given index.

Precondition
The supplied index must be the next available one; that is, indexes must be assigned sequentially.

Here is the call graph for this function:

void AddOutputPort ( std::unique_ptr< OutputPortBase port)
inlineprotected

(Internal use only) Adds an already-constructed 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.

Here is the call graph for this function:

Here is the caller graph for this function:

static DependencyTicket all_input_ports_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all input ports u of this system.

static DependencyTicket all_parameters_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa.

static DependencyTicket all_sources_ticket ( )
inlinestatic

Returns a ticket indicating dependence on every possible independent source value, including time, state, input ports, parameters, and the accuracy setting (but not cache entries).

This is the default dependency for computations that have not specified anything more refined.

Here is the caller graph for this function:

static DependencyTicket all_state_ticket ( )
inlinestatic

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, 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<ContextBase> AllocateContext ( ) const
inline

Returns a Context suitable for use with this System.

Context resources are allocated based on resource requests that were made during System construction.

Here is the call graph for this function:

Here is the caller graph for this function:

DependencyTicket assign_next_dependency_ticket ( )
inlineprotected

(Internal use only) Assigns the next unused dependency ticket number, unique only within a particular system.

Each call to this method increments the ticket number.

Here is the caller graph for this function:

DependencyTicket cache_entry_ticket ( CacheIndex  index)
inline

Returns a ticket indicating dependence on the cache entry indicated by index.

Precondition
index selects an existing cache entry in this System.

Here is the call graph for this function:

void CheckValidContext ( const ContextBase context) const
inline

Checks whether the given context is valid for this System and throws an exception with a helpful message if not.

This is very expensive and should generally be done only in Debug builds, like this:

Here is the call graph for this function:

Here is the caller graph for this function:

static DependencyTicket configuration_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all the configuration variables for this System.

By default this is set to the continuous second-order state variables q, but configuration may be represented differently in some systems (discrete ones, for example), in which case this ticket should have been set to depend on that representation. This ticket also assumes that configuration computations may depend on any parameter and on the accuracy setting (which don't change often), but not on time. 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.

const CacheEntry & DeclareCacheEntry ( std::string  description,
CacheEntry::AllocCallback  alloc_function,
CacheEntry::CalcCallback  calc_function,
std::set< DependencyTicket prerequisites_of_calc = all_sources_ticket()} 
)

Declares a new CacheEntry in this System using the least-restrictive definitions for the associated functions.

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. The function signatures here are:

std::unique_ptr<AbstractValue> Alloc();
void Calc(const ContextBase&, AbstractValue*);

where the AbstractValue objects must resolve to the same concrete type.

Parameters
[in]descriptionA 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]alloc_functionGiven a Context, returns a heap-allocated AbstractValue object suitable for holding a value for this cache entry.
[in]calc_functionProvides the computation that maps from a given Context to the current value that this cache entry should have, and writes that value to a given object of the type returned by alloc_function.
[in]prerequisites_of_calcProvides 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.
Returns
a const reference to the newly-created CacheEntry.
Exceptions
std::logic_errorif given an explicitly empty prerequisite list.

Here is the caller graph for this function:

const CacheEntry & DeclareCacheEntry ( std::string  description,
ValueType(MySystem::*)() const  make,
void(MySystem::*)(const MyContext &, ValueType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = all_sources_ticket()} 
)

Declares a cache entry by specifying member functions to use both for the allocator and calculator.

The signatures are:

ValueType MySystem::MakeValueType() const;
void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;

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 first DeclareCacheEntry() signature above for more information about the parameters and behavior.

See also
drake::systems::Value

Here is the call graph for this function:

const CacheEntry & DeclareCacheEntry ( std::string  description,
const ValueType &  model_value,
void(MySystem::*)(const MyContext &, ValueType *) const  calc,
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:

void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;

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 first DeclareCacheEntry() signature above for more information about the parameters and behavior.

See also
drake::systems::Value

Here is the call graph for this function:

const CacheEntry & DeclareCacheEntry ( std::string  description,
void(MySystem::*)(const MyContext &, ValueType *) const  calc,
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:

void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;

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.

Note
The default constructor will be called once immediately to create a model value, and subsequent allocations will just copy the model value without invoking the constructor again. If you want the constructor invoked again at each allocation (not common), use one of the other signatures to explicitly provide a method for the allocator to call; that method can then invoke the ValueType default constructor each time it is called.
See also
drake::systems::Value

Here is the call graph for this function:

const CacheEntry & DeclareCacheEntryWithKnownTicket ( DependencyTicket  known_ticket,
std::string  description,
CacheEntry::AllocCallback  alloc_function,
CacheEntry::CalcCallback  calc_function,
std::set< DependencyTicket prerequisites_of_calc = all_sources_ticket()} 
)
protected

(Internal use only) This is for cache entries associated with pre-defined tickets, for example the cache entry for time derivatives.

See the public API for the most-general DeclareCacheEntry() signature for the meanings of the other parameters here.

Here is the caller graph for this function:

DependencyTicket discrete_state_ticket ( DiscreteStateIndex  index) const
inline

Returns a ticket indicating dependence on a particular discrete state variable (may be a vector).

(We sometimes refer to this as a "discrete variable group".)

virtual std::unique_ptr<ContextBase> DoAllocateContext ( ) const
protectedpure virtual

Derived class implementations should allocate a suitable concrete Context type, then invoke the above InitializeContextBase() method.

A Diagram must then invoke AllocateContext() to obtain each of the subcontexts for its DiagramContext, and must set up inter-subcontext dependencies among its children and between itself and its children. Then context resources such as parameters and state should be allocated.

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

Here is the caller graph for this function:

virtual void DoCheckValidContext ( const ContextBase ) const
protectedpure virtual

Derived classes must implement this to verify that the supplied Context is suitable, and throw an exception if not.

This is a runtime check but may be expensive so is not guaranteed to be invoked except in Debug builds.

Here is the caller graph for this function:

const AbstractValue* EvalAbstractInput ( const ContextBase context,
int  port_index 
) const
inline

Returns the value of the input port with the given port_index as an AbstractValue, which is permitted for ports of any type.

Causes the value to become up to date first if necessary, delegating to our parent Diagram. Returns a pointer to the port's value, or nullptr if the port is not connected. If you know the actual type, use one of the more-specific signatures.

Precondition
port_index selects an existing input port of this System.
See also
EvalInputValue(), System::EvalVectorInput(), System::EvalEigenVectorInput()

Here is the call graph for this function:

Here is the caller graph for this function:

const AbstractValue * EvalAbstractInputImpl ( const char *  func,
const ContextBase context,
InputPortIndex  port_index 
) const
protected

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

func should be the user-visible API function name obtained with func.

Here is the call graph for this function:

Here is the caller graph for this function:

const V* EvalInputValue ( const ContextBase context,
int  port_index 
) const
inline

Returns the value of an abstract-valued input port with the given port_index as a value of known type V.

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 V, or nullptr if the port is not connected.

Precondition
port_index selects an existing input port of this System.
the port's value must be retrievable from the stored abstract value using AbstractValue::GetValue<V>.
Template Parameters
VThe type of data expected.

Here is the call graph for this function:

const CacheEntry& get_cache_entry ( CacheIndex  index) const
inline

Return a reference to a CacheEntry given its index.

Here is the call graph for this function:

const InputPortBase& get_input_port_base ( InputPortIndex  port_index) const
inline

Returns a reference to an InputPort given its port_index.

Precondition
port_index selects an existing input port of this System.

Here is the call graph for this function:

const std::string& get_name ( ) const
inline

Returns the name last supplied to set_name(), if any.

Diagrams built with DiagramBuilder will always have a default name for every contained subsystem for which no user-provided name is available. Systems created by copying with a scalar type change have the same name as the source system. An empty string is returned if no name has been set.

Here is the caller graph for this function:

int get_num_input_ports ( ) const
inline

Returns the number of input ports currently allocated in this System.

These are indexed from 0 to get_num_input_ports()-1.

Here is the caller graph for this function:

int get_num_output_ports ( ) const
inline

Returns the number of output ports currently allocated in this System.

These are indexed from 0 to get_num_output_ports()-1.

Here is the caller graph for this function:

int get_num_total_inputs ( ) const
inline

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

int get_num_total_outputs ( ) const
inline

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

const OutputPortBase& get_output_port_base ( OutputPortIndex  port_index) const
inline

Returns a reference to an OutputPort given its port_index.

Precondition
port_index selects an existing output port of this System.

Here is the call graph for this function:

const internal::SystemParentServiceInterface* get_parent_service ( ) const
inlineprotected

Returns a pointer to the service interface of the immediately enclosing Diagram if one has been set, otherwise nullptr.

const InputPortBase& GetInputPortBaseOrThrow ( const char *  func,
int  port_index 
) const
inlineprotected

(Internal use only) Returns the InputPortBase at index port_index, throwing std::out_of_range we don't like the port index.

The name of the public API method that received the bad index is provided in func and is included in the error message.

Here is the call graph for this function:

Here is the caller graph for this function:

const OutputPortBase& GetOutputPortBaseOrThrow ( const char *  func,
int  port_index 
) const
inlineprotected

(Internal use only) Returns the OutputPortBase at index port_index, throwing std::out_of_range we don't like the port index.

The name of the public API method that received the bad index is provided in func and is included in the error message.

Here is the call graph for this function:

Here is the caller graph for this function:

const std::string& GetSystemName ( ) const
inlinefinal

Returns a human-readable name for this system, for use in messages and logging.

This will be the same as returned by get_name(), unless that would be an empty string. In that case we return a non-unique placeholder name, currently just "_" (a lone underscore).

Here is the call graph for this function:

std::string GetSystemPathname ( ) const
final

Generates and returns a human-readable full path name of this subsystem, for use in messages and logging.

The name starts from the root System, with "::" delimiters between parent and child subsystems, with the individual subsystems represented by their names as returned by GetSystemName().

Here is the caller graph for this function:

std::string GetSystemType ( ) const
inlinefinal

Returns the most-derived type of this concrete System object as a human-readable string suitable for use in error messages.

The format is as generated by NiceTypeName and will include namespace qualification if present.

See also
NiceTypeName for more specifics.

Here is the call graph for this function:

void InitializeContextBase ( ContextBase context) const
protected

This method must be invoked from within derived class DoAllocateContext() implementations right after the concrete Context object has been allocated.

It allocates cache entries, sets up all intra-Context dependencies, and marks the ContextBase as initialized so that we can verify proper derived-class behavior.

Precondition
The supplied context must not be null and must not already have been initialized.

Here is the call graph for this function:

Here is the caller graph for this function:

DependencyTicket input_port_ticket ( InputPortIndex  index)
inline

Returns a ticket indicating dependence on the input port indicated by index.

Precondition
index selects an existing input port of this System.

Here is the call graph for this function:

static DependencyTicket kinematics_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all of the configuration and velocity state variables of this System.

This ticket depends on the configuration_ticket and the velocity_ticket. Note that this includes dependence on all parameters and the accuracy setting, but not on time.

See also
configuration_ticket(), velocity_ticket()
static DependencyTicket nothing_ticket ( )
inlinestatic

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_abstract_parameters ( ) const
inline

Returns the number of declared abstract parameters.

Here is the caller graph for this function:

int num_abstract_states ( ) const
inline

Returns the number of declared abstract state variables.

Here is the caller graph for this function:

int num_cache_entries ( ) const
inline

Returns the number nc of cache entries currently allocated in this System.

These are indexed from 0 to nc-1.

Here is the caller graph for this function:

int num_discrete_state_groups ( ) const
inline

Returns the number of declared discrete state groups (each group is a vector-valued discrete state variable).

Here is the caller graph for this function:

int num_numeric_parameters ( ) const
inline

Returns the number of declared numeric parameters (each of these is a vector-valued parameter).

Here is the caller graph for this function:

DependencyTicket numeric_parameter_ticket ( NumericParameterIndex  index) const
inline

Returns a ticket indicating dependence on a particular numeric parameter (may be a vector).

SystemBase& operator= ( const SystemBase )
delete
SystemBase& operator= ( SystemBase &&  )
delete
DependencyTicket output_port_ticket ( OutputPortIndex  index)
inline

Returns a ticket indicating dependence on the output port indicated by index.

Precondition
index selects an existing output port of this System.

Here is the call graph for this function:

static DependencyTicket q_ticket ( )
inlinestatic

Returns a ticket indicating that a computation depends on configuration state variables q.

void set_name ( const std::string &  name)
inline

Sets the name of the system.

Do not use the path delimiter character ':' in the name. When creating a Diagram, names of sibling subsystems should be unique. DiagramBuilder uses this method to assign a unique default name if none is provided.

Here is the caller graph for this function:

static void set_parent_service ( SystemBase child,
const internal::SystemParentServiceInterface *  parent_service 
)
inlinestaticprotected

(Internal use only) Declares that parent_service is the service interface of the Diagram that owns this subsystem.

Aborts if the parent service has already been set to something else.

Here is the call graph for this function:

Here is the caller graph for this function:

void ThrowCantEvaluateInputPort ( const char *  func,
InputPortIndex  port_index 
) const
protected

Throws std::logic_error because someone called API method func, that requires this input port to be evaluatable, but the port was neither fixed nor connected.

Here is the caller graph for this function:

void ThrowIfContextNotCompatible ( const ContextBase context) const
inlinefinal

Throws an exception with an appropriate message if the given context is not compatible with this System.

Restrictions may vary for different systems; the error message should explain. This can be an expensive check so you may want to limit it to Debug builds.

Here is the call graph for this function:

void ThrowInputPortHasWrongType ( const char *  func,
InputPortIndex  port_index,
const std::string &  expected_type,
const std::string &  actual_type 
) const
protected

Throws std::logic_error because someone called API method func claiming the input port had some value type that was wrong.

Here is the caller graph for this function:

void ThrowInputPortIndexOutOfRange ( const char *  func,
InputPortIndex  port_index 
) const
protected

Throws std::out_of_range to report bad input port_index that was passed to API method func.

Here is the caller graph for this function:

void ThrowNegativePortIndex ( const char *  func,
int  port_index 
) const
protected

Throws std::out_of_range to report a negative port_index that was passed to API method func.

Caller must ensure that the function name makes it clear what kind of port we're complaining about.

Here is the caller graph for this function:

void ThrowNotAVectorInputPort ( const char *  func,
InputPortIndex  port_index 
) const
protected

Throws std::logic_error because someone misused API method func, that is only allowed for declared-vector input ports, on an abstract port whose index is given here.

Here is the caller graph for this function:

void ThrowOutputPortIndexOutOfRange ( const char *  func,
OutputPortIndex  port_index 
) const
protected

Throws std::out_of_range to report bad output port_index that was passed to API method func.

Here is the caller graph for this function:

static DependencyTicket time_ticket ( )
inlinestatic

Returns a ticket indicating dependence on time.

This is the same ticket for all systems and refers to the same time value.

static DependencyTicket v_ticket ( )
inlinestatic

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.

static DependencyTicket velocity_ticket ( )
inlinestatic

(Advanced) Returns a ticket indicating dependence on all of the velocity variables, but not the configuration variables for this System.

By default this is set to the continuous state variables v, but velocity may be represented differently in some systems (discrete ones, for example), in which case this ticket should have been set to depend on that representation. This ticket also assumes that velocity calculations may depend on any parameter and on the accuracy setting (which don't change often), but not on time. Examples: a parameter that affects length may change the computation of an end-effector velocity. A change in accuracy requirement may require recomputation of an iterative approximation of friction forces.

Warning
This does not include dependence on configuration, although most velocity calculations do depend on configuration. If you want to register dependence on both (more common), use kinematics_ticket().
static DependencyTicket xa_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all of the abstract state variables in the current Context.

static DependencyTicket xc_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all of the continuous state variables q, v, or z.

static DependencyTicket xcdot_ticket ( )
inlinestatic

Returns a ticket for the cache entry that holds time derivatives of the continuous variables.

static DependencyTicket xd_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group.

static DependencyTicket xdhat_ticket ( )
inlinestatic

Returns a ticket for the cache entry that holds the discrete state update for the numerical discrete variables in the state.

static DependencyTicket z_ticket ( )
inlinestatic

Returns a ticket indicating dependence on all of the miscellaneous continuous state variables z.


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