Drake
Context< T > Class Template Referenceabstract

Context is an abstract class template that represents all the typed values that are used in a System's computations: time, numeric-valued input ports, numerical state, and numerical parameters. More...

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

Inheritance diagram for Context< T >:
[legend]
Collaboration diagram for Context< T >:
[legend]

Public Member Functions

std::unique_ptr< Context< T > > Clone () const
 Returns a deep copy of this Context. More...
 
 ~Context () override=default
 
const T & get_time () const
 Returns the current time in seconds. More...
 
virtual void set_time (const T &time_sec)
 Set the current time in seconds. More...
 
virtual const State< T > & get_state () const =0
 
virtual State< T > & get_mutable_state ()=0
 
bool is_stateless () const
 Returns true if the Context has no state. More...
 
bool has_only_continuous_state () const
 Returns true if the Context has continuous state, but no discrete or abstract state. More...
 
bool has_only_discrete_state () const
 Returns true if the Context has discrete state, but no continuous or abstract state. More...
 
int get_num_total_states () const
 Returns the total dimension of all of the basic vector states (as if they were muxed). More...
 
ContinuousState< T > & get_mutable_continuous_state ()
 Returns a mutable reference to the continuous component of the state, which may be of size zero. More...
 
VectorBase< T > & get_mutable_continuous_state_vector ()
 Returns a mutable reference to the continuous state vector, devoid of second-order structure. More...
 
const ContinuousState< T > & get_continuous_state () const
 Returns a const reference to the continuous component of the state, which may be of size zero. More...
 
const VectorBase< T > & get_continuous_state_vector () const
 Returns a reference to the continuous state vector, devoid of second-order structure. More...
 
int get_num_discrete_state_groups () const
 Returns the number of vectors (groups) in the discrete state. More...
 
const DiscreteValues< T > & get_discrete_state () const
 Returns a reference to the entire discrete state, which may consist of multiple discrete state vectors (groups). More...
 
const BasicVector< T > & get_discrete_state_vector () const
 Returns a reference to the only discrete state vector. More...
 
DiscreteValues< T > & get_mutable_discrete_state ()
 Returns a mutable reference to the discrete component of the state, which may be of size zero. More...
 
BasicVector< T > & get_mutable_discrete_state_vector ()
 Returns a mutable reference to the only discrete state vector. More...
 
BasicVector< T > & get_mutable_discrete_state (int index)
 Returns a mutable reference to group (vector) index of the discrete state. More...
 
const BasicVector< T > & get_discrete_state (int index) const
 Returns a const reference to group (vector) index of the discrete state. More...
 
int get_num_abstract_states () const
 Returns the number of elements in the abstract state. More...
 
const AbstractValuesget_abstract_state () const
 Returns a const reference to the abstract component of the state, which may be of size zero. More...
 
AbstractValuesget_mutable_abstract_state ()
 Returns a mutable reference to the abstract component of the state, which may be of size zero. More...
 
template<typename U >
U & get_mutable_abstract_state (int index)
 Returns a mutable reference to element index of the abstract state. More...
 
template<typename U >
const U & get_abstract_state (int index) const
 Returns a const reference to the abstract component of the state at index. More...
 
FixedInputPortValueFixInputPort (int index, const BasicVector< T > &vec)
 Connects the input port at index to a FixedInputPortValue with the given vector vec. More...
 
FixedInputPortValueFixInputPort (int index, const Eigen::Ref< const VectorX< T >> &data)
 Same as above method but starts with an Eigen vector whose contents are used to initialize a BasicVector in the FixedInputPortValue. More...
 
FixedInputPortValueFixInputPort (int index, std::unique_ptr< BasicVector< T >> vec)
 Same as the above method that takes a const BasicVector<T>&, but here the vector is passed by unique_ptr instead of by const reference. More...
 
const Parameters< T > & get_parameters () const
 Returns a const reference to this Context's parameters. More...
 
Parameters< T > & get_mutable_parameters ()
 Returns a mutable reference to this Context's parameters. More...
 
int num_numeric_parameters () const
 Returns the number of vector-valued parameters. More...
 
const BasicVector< T > & get_numeric_parameter (int index) const
 Returns a const reference to the vector-valued parameter at index. More...
 
BasicVector< T > & get_mutable_numeric_parameter (int index)
 Returns a mutable reference to element index of the vector-valued parameters. More...
 
int num_abstract_parameters () const
 Returns the number of abstract-valued parameters. More...
 
const AbstractValueget_abstract_parameter (int index) const
 Returns a const reference to the abstract-valued parameter at index. More...
 
AbstractValueget_mutable_abstract_parameter (int index)
 Returns a mutable reference to element index of the abstract-valued parameters. More...
 
virtual void set_accuracy (const optional< double > &accuracy)
 Records the user's requested accuracy. More...
 
const optional< double > & get_accuracy () const
 Returns the accuracy setting (if any). More...
 
std::unique_ptr< State< T > > CloneState () const
 Returns a deep copy of this Context's State. More...
 
void SetTimeStateAndParametersFrom (const Context< double > &source)
 Initializes this context's time, state, and parameters from the real values in source, regardless of this context's scalar type. More...
 
Does not allow copy, move, or assignment.
 Context (Context &&)=delete
 
Contextoperator= (const Context &)=delete
 
Contextoperator= (Context &&)=delete
 
- Public Member Functions inherited from ContextBase
std::unique_ptr< ContextBaseClone () const
 Creates an identical copy of the concrete context object. More...
 
 ~ContextBase () override
 
void DisableCaching () const
 (Debugging) Disables caching recursively for this context and all its subcontexts. More...
 
void EnableCaching () const
 (Debugging) Re-enables caching recursively for this context and all its subcontexts. More...
 
void SetAllCacheEntriesOutOfDate () const
 (Debugging) Marks all cache entries out of date, recursively for this context and all its subcontexts. More...
 
const std::string & GetSystemName () const final
 Returns the local name of the subsystem for which this is the Context. More...
 
std::string GetSystemPathname () const final
 Returns the full pathname of the subsystem for which this is the Context. More...
 
const Cacheget_cache () const
 Returns a const reference to this subcontext's cache. More...
 
Cacheget_mutable_cache () const
 (Advanced) Returns a mutable reference to this subcontext's cache. More...
 
const DependencyTrackerget_tracker (DependencyTicket ticket) const
 Returns a const reference to a DependencyTracker in this subcontext. More...
 
DependencyTrackerget_mutable_tracker (DependencyTicket ticket)
 Returns a mutable reference to a DependencyTracker in this subcontext. More...
 
const DependencyGraphget_dependency_graph () const
 Returns a const reference to the collection of value trackers within this subcontext. More...
 
DependencyGraphget_mutable_dependency_graph ()
 Returns a mutable reference to the dependency graph. More...
 
int get_num_input_ports () const
 Returns the number of input ports in this context. More...
 
int get_num_output_ports () const
 Returns the number of output ports represented in this context. More...
 
DependencyTicket input_port_ticket (InputPortIndex port_num)
 Returns the dependency ticket associated with a particular input port. More...
 
DependencyTicket output_port_ticket (OutputPortIndex port_num)
 Returns the dependency ticket associated with a particular output port. More...
 
FixedInputPortValueFixInputPort (int index, std::unique_ptr< AbstractValue > value)
 Connects the input port at index to a FixedInputPortValue with the given abstract value. More...
 
FixedInputPortValueFixInputPort (int index, const AbstractValue &value)
 Same as above method but the value is passed by const reference instead of by unique_ptr. More...
 
const FixedInputPortValueMaybeGetFixedInputPortValue (int index) const
 For input port index, returns a const FixedInputPortValue if the port is fixed, otherwise nullptr. More...
 
FixedInputPortValueMaybeGetMutableFixedInputPortValue (int index)
 For input port index, returns a mutable FixedInputPortValue if the port is fixed, otherwise nullptr. More...
 
 ContextBase (ContextBase &&)=delete
 
ContextBaseoperator= (const ContextBase &)=delete
 
ContextBaseoperator= (ContextBase &&)=delete
 

Protected Member Functions

 Context ()=default
 
 Context (const Context< T > &)=default
 Copy constructor takes care of base class and Context<T> data members. More...
 
virtual std::unique_ptr< State< T > > DoCloneState () const =0
 Override to return the appropriate concrete State class to be returned by CloneState(). More...
 
const StepInfo< T > & get_step_info () const
 Returns a const reference to current time and step information. More...
 
void init_continuous_state (std::unique_ptr< ContinuousState< T >> xc)
 Sets the continuous state to xc, deleting whatever was there before. More...
 
void init_discrete_state (std::unique_ptr< DiscreteValues< T >> xd)
 Sets the discrete state to xd, deleting whatever was there before. More...
 
void init_abstract_state (std::unique_ptr< AbstractValues > xa)
 Sets the abstract state to xa, deleting whatever was there before. More...
 
void init_parameters (std::unique_ptr< Parameters< T >> params)
 Sets the parameters to params, deleting whatever was there before. More...
 
- Protected Member Functions inherited from ContextBase
 ContextBase ()
 Default constructor creates an empty ContextBase but initializes all the built-in dependency trackers that are the same in every System (like time, q, all states, all inputs, etc.). More...
 
 ContextBase (const ContextBase &)=default
 Copy constructor takes care of base class data members, but does not fix up base class pointers. More...
 
void AddInputPort (InputPortIndex expected_index, DependencyTicket ticket)
 Adds the next input port. More...
 
void AddOutputPort (OutputPortIndex expected_index, DependencyTicket ticket, const internal::OutputPortPrerequisite &prerequisite)
 Adds the next output port. More...
 
virtual std::unique_ptr< ContextBaseDoCloneWithoutPointers () const =0
 Derived classes must implement this so that it performs the complete deep copy of the context, including all base class members but not fixing up base class pointers. More...
 
virtual void DoPropagateBuildTrackerPointerMap (const ContextBase &clone, DependencyTracker::PointerMap *tracker_map) const
 DiagramContext must implement this to invoke BuildTrackerPointerMap() on each of its subcontexts. More...
 
virtual void DoPropagateFixContextPointers (const ContextBase &source, const DependencyTracker::PointerMap &tracker_map)
 DiagramContext must implement this to invoke FixContextPointers() on each of its subcontexts. More...
 
virtual void DoPropagateCachingChange (void(Cache::*caching_change)()) const
 DiagramContext must implement this to invoke a caching behavior change on each of its subcontexts. More...
 

Static Protected Member Functions

static std::unique_ptr< Context< T > > CloneWithoutPointers (const Context< T > &source)
 Clones a context but without any of its internal pointers. More...
 
- Static Protected Member Functions inherited from ContextBase
static std::unique_ptr< ContextBaseCloneWithoutPointers (const ContextBase &source)
 Clones a context but without copying any of its internal pointers; the clone's pointers are set to null. More...
 
static void BuildTrackerPointerMap (const ContextBase &source, const ContextBase &clone, DependencyTracker::PointerMap *tracker_map)
 (Internal use only) Given a new context clone containing an identically-structured dependency graph as the one in source, creates a mapping of all tracker memory addresses from source to clone. More...
 
static void FixContextPointers (const ContextBase &source, const DependencyTracker::PointerMap &tracker_map, ContextBase *clone)
 (Internal use only) Assuming clone is a recently-cloned Context that has yet to have its internal pointers updated, sets those pointers now. More...
 
static void PropagateCachingChange (const ContextBase &context, void(Cache::*caching_change)())
 (Internal use only) Applies the given caching-change notification method to context, and propagates the notification to subcontexts if context is a DiagramContext. More...
 
static void set_parent (ContextBase *child, const ContextBase *parent)
 Declares that parent is the context of the enclosing Diagram. More...
 

Detailed Description

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

Context is an abstract class template that represents all the typed values that are used in a System's computations: time, numeric-valued input ports, numerical state, and numerical parameters.

There are also type-erased abstract state variables, abstract-valued input ports, abstract parameters, and a double accuracy setting. The framework provides two concrete subclasses of Context: LeafContext (for leaf Systems) and DiagramContext (for composite System Diagrams). Users are forbidden to extend DiagramContext and are discouraged from subclassing LeafContext.

Template Parameters
TThe mathematical type of the context, which must be a valid Eigen scalar.

Constructor & Destructor Documentation

Context ( Context< T > &&  )
delete
~Context ( )
overridedefault
Context ( )
protecteddefault
Context ( const Context< T > &  )
protecteddefault

Copy constructor takes care of base class and Context<T> data members.

Derived classes must implement copy constructors that delegate to this one for use in their DoCloneWithoutPointers() implementations.

Member Function Documentation

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

Returns a deep copy of this Context.

Here is the caller graph for this function:

std::unique_ptr<State<T> > CloneState ( ) const
inline

Returns a deep copy of this Context's State.

Here is the caller graph for this function:

static std::unique_ptr<Context<T> > CloneWithoutPointers ( const Context< T > &  source)
inlinestaticprotected

Clones a context but without any of its internal pointers.

virtual std::unique_ptr<State<T> > DoCloneState ( ) const
protectedpure virtual

Override to return the appropriate concrete State class to be returned by CloneState().

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

FixedInputPortValue& FixInputPort ( int  index,
const BasicVector< T > &  vec 
)
inline

Connects the input port at index to a FixedInputPortValue with the given vector vec.

Aborts if index is out of range. Returns a reference to the allocated FixedInputPortValue. The reference will remain valid until this input port's value source is replaced or the Context is destroyed. You may use that reference to modify the input port's value using the appropriate FixedInputPortValue method, which will ensure that invalidation notifications are delivered.

Here is the caller graph for this function:

FixedInputPortValue& FixInputPort ( int  index,
const Eigen::Ref< const VectorX< T >> &  data 
)
inline

Same as above method but starts with an Eigen vector whose contents are used to initialize a BasicVector in the FixedInputPortValue.

FixedInputPortValue& FixInputPort ( int  index,
std::unique_ptr< BasicVector< T >>  vec 
)
inline

Same as the above method that takes a const BasicVector<T>&, but here the vector is passed by unique_ptr instead of by const reference.

The caller must not retain any aliases to vec; within this method, vec is cloned and then deleted.

Note
This overload will become deprecated in the future, because it can mislead users to believe that they can retain an alias of vec to mutate the fixed value during a simulation. Callers should prefer to use one of the other overloads instead.
const AbstractValue& get_abstract_parameter ( int  index) const
inline

Returns a const reference to the abstract-valued parameter at index.

Precondition
index must identify an existing parameter.
const AbstractValues& get_abstract_state ( ) const
inline

Returns a const reference to the abstract component of the state, which may be of size zero.

Here is the caller graph for this function:

const U& get_abstract_state ( int  index) const
inline

Returns a const reference to the abstract component of the state at index.

Precondition
index must identify an existing element.
const optional<double>& get_accuracy ( ) const
inline

Returns the accuracy setting (if any).

See also
set_accuracy() for details.

Here is the caller graph for this function:

const ContinuousState<T>& get_continuous_state ( ) const
inline

Returns a const reference to the continuous component of the state, which may be of size zero.

Here is the caller graph for this function:

const VectorBase<T>& get_continuous_state_vector ( ) const
inline

Returns a reference to the continuous state vector, devoid of second-order structure.

The vector may be of size zero.

Here is the caller graph for this function:

const DiscreteValues<T>& get_discrete_state ( ) const
inline

Returns a reference to the entire discrete state, which may consist of multiple discrete state vectors (groups).

Here is the caller graph for this function:

const BasicVector<T>& get_discrete_state ( int  index) const
inline

Returns a const reference to group (vector) index of the discrete state.

Precondition
index must identify an existing group.
const BasicVector<T>& get_discrete_state_vector ( ) const
inline

Returns a reference to the only discrete state vector.

The vector may be of size zero.

Precondition
There is only one discrete state group.
AbstractValue& get_mutable_abstract_parameter ( int  index)
inline

Returns a mutable reference to element index of the abstract-valued parameters.

Precondition
index must identify an existing parameter.
AbstractValues& get_mutable_abstract_state ( )
inline

Returns a mutable reference to the abstract component of the state, which may be of size zero.

U& get_mutable_abstract_state ( int  index)
inline

Returns a mutable reference to element index of the abstract state.

Precondition
index must identify an existing element.
ContinuousState<T>& get_mutable_continuous_state ( )
inline

Returns a mutable reference to the continuous component of the state, which may be of size zero.

Here is the caller graph for this function:

VectorBase<T>& get_mutable_continuous_state_vector ( )
inline

Returns a mutable reference to the continuous state vector, devoid of second-order structure.

The vector may be of size zero.

Here is the caller graph for this function:

DiscreteValues<T>& get_mutable_discrete_state ( )
inline

Returns a mutable reference to the discrete component of the state, which may be of size zero.

Here is the caller graph for this function:

BasicVector<T>& get_mutable_discrete_state ( int  index)
inline

Returns a mutable reference to group (vector) index of the discrete state.

Precondition
index must identify an existing group.
BasicVector<T>& get_mutable_discrete_state_vector ( )
inline

Returns a mutable reference to the only discrete state vector.

See also
get_discrete_state_vector().
Precondition
There is only one discrete state group.
BasicVector<T>& get_mutable_numeric_parameter ( int  index)
inline

Returns a mutable reference to element index of the vector-valued parameters.

Precondition
index must identify an existing parameter.

Here is the caller graph for this function:

Parameters<T>& get_mutable_parameters ( )
inline

Returns a mutable reference to this Context's parameters.

Here is the caller graph for this function:

virtual State<T>& get_mutable_state ( )
pure virtual

Implemented in DiagramContext< T >, DiagramContext< double >, LeafContext< T >, and LeafContext< double >.

Here is the caller graph for this function:

int get_num_abstract_states ( ) const
inline

Returns the number of elements in the abstract state.

Here is the caller graph for this function:

int get_num_discrete_state_groups ( ) const
inline

Returns the number of vectors (groups) in the discrete state.

Here is the caller graph for this function:

int get_num_total_states ( ) const
inline

Returns the total dimension of all of the basic vector states (as if they were muxed).

Exceptions
std::runtime_errorif the system contains any abstract state.

Here is the caller graph for this function:

const BasicVector<T>& get_numeric_parameter ( int  index) const
inline

Returns a const reference to the vector-valued parameter at index.

Precondition
index must identify an existing parameter.

Here is the caller graph for this function:

const Parameters<T>& get_parameters ( ) const
inline

Returns a const reference to this Context's parameters.

Here is the caller graph for this function:

virtual const State<T>& get_state ( ) const
pure virtual

Implemented in DiagramContext< T >, DiagramContext< double >, LeafContext< T >, and LeafContext< double >.

Here is the caller graph for this function:

const StepInfo<T>& get_step_info ( ) const
inlineprotected

Returns a const reference to current time and step information.

const T& get_time ( ) const
inline

Returns the current time in seconds.

Here is the caller graph for this function:

bool has_only_continuous_state ( ) const
inline

Returns true if the Context has continuous state, but no discrete or abstract state.

Here is the caller graph for this function:

bool has_only_discrete_state ( ) const
inline

Returns true if the Context has discrete state, but no continuous or abstract state.

Here is the caller graph for this function:

void init_abstract_state ( std::unique_ptr< AbstractValues xa)
inlineprotected

Sets the abstract state to xa, deleting whatever was there before.

Invalidates all abstract state-dependent computations in this context and its subcontexts.

void init_continuous_state ( std::unique_ptr< ContinuousState< T >>  xc)
inlineprotected

Sets the continuous state to xc, deleting whatever was there before.

Invalidates all continuous state-dependent computations in this context and its subcontexts.

Here is the caller graph for this function:

void init_discrete_state ( std::unique_ptr< DiscreteValues< T >>  xd)
inlineprotected

Sets the discrete state to xd, deleting whatever was there before.

Invalidates all discrete state-dependent computations in this context and its subcontexts.

Here is the caller graph for this function:

void init_parameters ( std::unique_ptr< Parameters< T >>  params)
inlineprotected

Sets the parameters to params, deleting whatever was there before.

You must supply a Parameters object; null is not acceptable. Invalidates all parameter-dependent computations recursively in this context and its subcontexts.

bool is_stateless ( ) const
inline

Returns true if the Context has no state.

Here is the caller graph for this function:

int num_abstract_parameters ( ) const
inline

Returns the number of abstract-valued parameters.

Here is the caller graph for this function:

int num_numeric_parameters ( ) const
inline

Returns the number of vector-valued parameters.

Here is the caller graph for this function:

Context& operator= ( const Context< T > &  )
delete
Context& operator= ( Context< T > &&  )
delete
virtual void set_accuracy ( const optional< double > &  accuracy)
inlinevirtual

Records the user's requested accuracy.

If no accuracy is requested, computations are free to choose suitable defaults, or to refuse to proceed without an explicit accuracy setting.

Requested accuracy is stored in the Context for two reasons:

  • It permits all computations performed over a System to see the same accuracy request since accuracy is stored in one shared place, and
  • it allows us to invalidate accuracy-dependent cached computations when the requested accuracy has changed.

The accuracy of a complete simulation or other numerical study depends on the accuracy of all contributing computations, so it is important that each computation is done in accordance with the overall requested accuracy. Some examples of where this is needed:

  • Error-controlled numerical integrators use the accuracy setting to decide what step sizes to take.
  • The Simulator employs a numerical integrator, but also uses accuracy to decide how precisely to isolate witness function zero crossings.
  • Iterative calculations reported as results or cached internally depend on accuracy to decide how strictly to converge the results. Examples of these are: constraint projection, calculation of distances between smooth shapes, and deformation calculations for soft contact.

The common thread among these examples is that they all share the same Context, so by keeping accuracy here it can be used effectively to control all accuracy-dependent computations.

Reimplemented in DiagramContext< T >, and DiagramContext< double >.

Here is the caller graph for this function:

virtual void set_time ( const T &  time_sec)
inlinevirtual

Set the current time in seconds.

Reimplemented in DiagramContext< T >, and DiagramContext< double >.

Here is the caller graph for this function:

void SetTimeStateAndParametersFrom ( const Context< double > &  source)
inline

Initializes this context's time, state, and parameters from the real values in source, regardless of this context's scalar type.

Requires a constructor T(double).


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