Drake
Drake C++ Documentation
Context< T > Class Template Referenceabstract

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.

A Context is designed to be used only with the System that created it. Data encapsulated with State and Parameter objects can be copied between contexts for compatible systems with some restrictions. For details, see System Compatibility.

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

Does not allow copy, move, or assignment.
 Context (Context &&)=delete
 
Contextoperator= (const Context &)=delete
 
Contextoperator= (Context &&)=delete
 
Accessors for locally-stored values

Methods in this group provide const access to values stored locally in this Context.

The available values are:

  • time
  • state
  • parameters
  • accuracy

Fixed input port values and cached values (including output port values) are also stored in the Context but are accessed indirectly via methods like SystemBase::EvalInputValue(), through CacheEntry and OutputPort objects, or via the FixedInputPortValue object that was returned when an input port value was set.

See also
FixInputPort()
const T & get_time () const
 Returns the current time in seconds. More...
 
const State< T > & get_state () const
 Returns a const reference to the whole State. More...
 
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 num_total_states () const
 Returns the total dimension of all of the basic vector states (as if they were muxed). More...
 
int num_continuous_states () const
 Returns the number of continuous state variables xc = {q, v, z}. 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 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...
 
const BasicVector< T > & get_discrete_state (int index) const
 Returns a const reference to group (vector) index of the discrete state. More...
 
int 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...
 
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...
 
const std::optional< double > & get_accuracy () const
 Returns the accuracy setting (if any). More...
 
const Parameters< T > & get_parameters () const
 Returns a const reference to this Context's parameters. More...
 
int num_numeric_parameter_groups () 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...
 
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...
 
Methods for changing locally-stored values

Methods in this group allow changes to the values of quantities stored locally in this Context. The changeable quantities are:

  • time
  • state
  • parameters
  • accuracy
  • fixed input port values

Expensive computations may be performed that depend on the current values of some or all of the above quantities. For efficiency, we save the results of such computations in the Context so that we can reuse those results without unnecessary recomputation.

Terminology

We call a quantity whose value is needed in order to perform a particular computation a prerequisite of that computation, and we say that the computation is a dependent of that prerequisite. If a prerequisite's value changes, a result computed using an earlier value is invalid; we say that the prerequisite change invalidates that result, and that the result is out of date with respect to its prerequisites. It is important to note that the result of one computation can serve as a prerequisite to another computation; we call the dependent computation a downstream computation and the prerequisite an upstream computation.

Caching

Drake provides a caching system that is responsible for

  • storing computed results in the Context's cache, and
  • ensuring that any cached result that may be invalid is marked "out of date".

The correctness of results reported by Drake depends critically on every cached result being correctly flagged as up to date or out of date with respect to its prerequisites. Only when it is known for certain that a result is valid can it be marked up to date. Access to cached results is performed through Eval() methods that return up to date results immediately but initiate recomputation first for results marked out of date. The methods in the group below are responsible for ensuring that cached results are marked out of date whenever a prerequisite value may have changed. These methods do not initiate such recomputation themselves.

See also
System Cache Design and Implementation Notes

Invalidation and "out of date" notification

Each method in this group provides the ability to change a particular subset of the available quantities listed above. This triggers "out of date" notifications to the cached results for all computations for which any element of that subset is a prerequisite. Such notifications propagate to downstream computations, whose cached results may reside anywhere in the full Diagram context tree of which this Context is a part. That ensures that "out of date" flags are set correctly for the cached results of all computations that could be made invalid by a value change to any of the affected subset of quantities. We call this process a notification sweep.

Which method to use

Choose the most-specific method in this group that permits you to perform the modifications you need. For example, if you need to modify only continuous state variables, don't use a method that provides mutable access to the whole state. That provides two performance advantages:

  • fewer downstream computations need to be marked out of date, making the notification sweep faster, and
  • fewer results will need to be recomputed later.

The methods below may be grouped into "safe" methods that only set values in the context, and "dangerous" methods return a mutable reference. In addition, the FixInputPort methods return an object that has its own dangerous methods (see FixedInputPortValue). Prefer the safe methods when possible.

Safe "Set" methods

The set and Set methods that don't also contain GetMutable in their names are safe in the sense that they perform both the "mark as out of date" notification sweep through dependent cached results and the update to the local quantity's value. They do not return a reference to the value object. Using these methods ensures that no value modification can occur without an appropriate notification sweep. Also, these methods can be used to perform multiple changes at once (say time and state), requiring only a single notification sweep, and may perform optimizations to avoid notifications in case some of the new values are the same as the old ones.

Dangerous "GetMutable" methods

The GetMutable methods return a mutable reference to the local value object within this Context. The notification sweep is done prior to returning that reference. You can then use the reference to make the desired change. Note that with these methods we do not actually know whether dependent computations are invalid; that depends what you do with the reference once you have it. Nevertheless you will pay the cost of the notifications sweep immediately and the cost of recomputation later when you ask for the value. So don't call one of these methods unless you are certain you will be writing through the returned reference.

You must not hold on to the returned reference expecting to be able to make subsequent changes, because those changes can't be seen by the framework and thus will not cause the necessary notification sweep to occur. Instead, request the mutable reference again when you need it so that the necessary notification sweep can be performed.

The dangerous methods are segregated into their own documentation group.

Advanced context-modifying methods

Specialized methods are provided for expert users implementing integrators and other state-modifying solvers. Those are segregated to a separate documentation group.

Implementation note

Each method in the group below guarantees to mark as out of date any dependents of the quantities to which it permits modification, including all downstream dependents. However, the current implementations may also perform some unnecessary notifications. If so, that is noted in the method documentation. You should still use the most-specific available method so that you will benefit from later improvements that result in fewer notifications.

void SetTime (const T &time_sec)
 Sets the current time in seconds. More...
 
void SetContinuousState (const Eigen::Ref< const VectorX< T >> &xc)
 Sets the continuous state to xc, including q, v, and z partitions. More...
 
void SetTimeAndContinuousState (const T &time_sec, const Eigen::Ref< const VectorX< T >> &xc)
 Sets time to time_sec and continuous state to xc. More...
 
void SetDiscreteState (const Eigen::Ref< const VectorX< T >> &xd)
 Sets the discrete state to xd, assuming there is just one discrete state group. More...
 
void SetDiscreteState (int group_index, const Eigen::Ref< const VectorX< T >> &xd)
 Sets the discrete state group indicated by group_index to xd. More...
 
void SetDiscreteState (const DiscreteValues< T > &xd)
 Sets all the discrete state variables in this Context from a compatible DiscreteValues object. More...
 
template<typename ValueType >
void SetAbstractState (int index, const ValueType &value)
 Sets the value of the abstract state variable selected by index. More...
 
template<typename U >
void SetStateAndParametersFrom (const Context< U > &source)
 Copies all state and parameters in source, where numerical values are of type U, to this context. More...
 
template<typename U >
void SetTimeStateAndParametersFrom (const Context< U > &source)
 Copies time, accuracy, all state and all parameters in source, where numerical values are of type U, to this context. More...
 
void SetAccuracy (const std::optional< double > &accuracy)
 Records the user's requested accuracy, which is a unit-less quantity designed for use with simulation and other numerical studies. More...
 
FixedInputPortValueFixInputPort (int index, const AbstractValue &value)
 (Advanced) Connects the input port at index to a FixedInputPortValue with the given abstract value. More...
 
Dangerous methods for changing locally-stored values

Methods in this group return mutable references into the state and parameters in the Context. Although they do issue out-of-date notifications when invoked, so you can safely write to the reference once, there is no way to issue notifications if you make subsequent changes. So you must not hold these references for writing. See Dangerous GetMutable methods for more information.

State< T > & get_mutable_state ()
 Returns a mutable reference to the whole State, potentially invalidating all state-dependent computations so requiring out of date notifications to be made for all such computations. 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...
 
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...
 
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...
 
Parameters< T > & get_mutable_parameters ()
 Returns a mutable reference to this Context's parameters. More...
 
BasicVector< T > & get_mutable_numeric_parameter (int index)
 Returns a mutable reference to element index of the vector-valued (numeric) parameters. More...
 
AbstractValueget_mutable_abstract_parameter (int index)
 Returns a mutable reference to element index of the abstract-valued parameters. More...
 
Advanced methods for changing locally-stored values

Methods in this group are specialized for expert users writing numerical integrators and other context-modifying solvers where careful cache management can improve performance. Please see Context Value-Change Methods for general information, and prefer to use the methods in that section unless you really know what you're doing!

VectorBase< T > & SetTimeAndGetMutableContinuousStateVector (const T &time_sec)
 (Advanced) Sets time and returns a mutable reference to the continuous state xc (including q, v, z) as a VectorBase. More...
 
VectorBase< T > & SetTimeAndGetMutableQVector (const T &time_sec)
 (Advanced) Sets time and returns a mutable reference to the second-order continuous state partition q from xc. More...
 
std::pair< VectorBase< T > *, VectorBase< T > * > GetMutableVZVectors ()
 (Advanced) Returns mutable references to the first-order continuous state partitions v and z from xc. More...
 
void SetTimeAndNoteContinuousStateChange (const T &time_sec)
 (Advanced) Sets time and registers an intention to modify the continuous state xc. More...
 
void NoteContinuousStateChange ()
 (Advanced) Registers an intention to modify the continuous state xc. More...
 
Miscellaneous public methods
std::unique_ptr< Context< T > > Clone () const
 Returns a deep copy of this Context. More...
 
std::unique_ptr< State< T > > CloneState () const
 Returns a deep copy of this Context's State. More...
 
std::string to_string () const
 Returns a partial textual description of the Context, intended to be human-readable. More...
 
- 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...
 
void FreezeCache () const
 (Advanced) Freezes the cache at its current contents, preventing any further cache updates. More...
 
void UnfreezeCache () const
 (Advanced) Unfreezes the cache if it was previously frozen. More...
 
bool is_cache_frozen () const final
 (Advanced) Reports whether this Context's cache is currently frozen. More...
 
const std::string & GetSystemName () const final
 Returns the local name of the subsystem for which this is the Context. More...
 
internal::SystemId get_system_id () const
 (Internal) Gets the id of the subsystem that created this 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 num_input_ports () const
 Returns the number of input ports in this context. More...
 
int 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, const AbstractValue &value)
 (Advanced) Connects the input port at index to a FixedInputPortValue with the given abstract value. 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...
 
int64_t start_new_change_event () const
 (Internal use only) Returns the next change event serial number that is unique for this entire Context tree, not just this subcontext. More...
 
bool is_root_context () const
 Returns true if this context has no parent. More...
 
 ContextBase (ContextBase &&)=delete
 
ContextBaseoperator= (const ContextBase &)=delete
 
ContextBaseoperator= (ContextBase &&)=delete
 

Protected Member Functions

 Context ()
 
 Context (const Context< T > &)
 Copy constructor takes care of base class and Context<T> data members. More...
 
virtual const State< T > & do_access_state () const =0
 Returns a const reference to its concrete State object. More...
 
virtual State< T > & do_access_mutable_state ()=0
 Returns a mutable reference to its concrete State object without any invalidation. More...
 
virtual std::unique_ptr< State< T > > DoCloneState () const =0
 Returns the appropriate concrete State object to be returned by CloneState(). More...
 
virtual std::string do_to_string () const =0
 Returns a partial textual description of the Context, intended to be human-readable. More...
 
virtual void DoPropagateTimeChange (const T &time_sec, const std::optional< T > &true_time, int64_t change_event)
 Invokes PropagateTimeChange() on all subcontexts of this Context. More...
 
virtual void DoPropagateAccuracyChange (const std::optional< double > &accuracy, int64_t change_event)
 Invokes PropagateAccuracyChange() on all subcontexts of this Context. More...
 
void init_continuous_state (std::unique_ptr< ContinuousState< T >> xc)
 (Internal use only) Sets the continuous state to xc, deleting whatever was there before. More...
 
void init_discrete_state (std::unique_ptr< DiscreteValues< T >> xd)
 (Internal use only) Sets the discrete state to xd, deleting whatever was there before. More...
 
void init_abstract_state (std::unique_ptr< AbstractValues > xa)
 (Internal use only) Sets the abstract state to xa, deleting whatever was there before. More...
 
void init_parameters (std::unique_ptr< Parameters< T >> params)
 (Internal use only) 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...
 
bool owns_any_variables_or_parameters () const
 (Internal use only) Returns true if this context provides resources for its own individual state variables or parameters. More...
 
void PropagateBulkChange (int64_t change_event, void(ContextBase::*note_bulk_change)(int64_t change_event))
 (Internal use only) This is a convenience method for invoking the eponymous static method on this context (which occurs frequently). 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...
 
virtual void DoPropagateBulkChange (int64_t change_event, void(ContextBase::*note_bulk_change)(int64_t change_event))
 DiagramContext must implement this to invoke PropagateBulkChange() on its subcontexts, passing along the indicated method that specifies the particular bulk change (e.g. More...
 
void AddInputPort (InputPortIndex expected_index, DependencyTicket ticket, std::function< void(const AbstractValue &)> fixed_input_type_checker)
 Adds the next input port. More...
 
void AddOutputPort (OutputPortIndex expected_index, DependencyTicket ticket, const internal::OutputPortPrerequisite &prerequisite)
 Adds the next output port. More...
 
void AddDiscreteStateTicket (DependencyTicket ticket)
 Adds a ticket to the list of discrete state tickets. More...
 
void AddAbstractStateTicket (DependencyTicket ticket)
 Adds a ticket to the list of abstract state tickets. More...
 
void AddNumericParameterTicket (DependencyTicket ticket)
 Adds a ticket to the list of numeric parameter tickets. More...
 
void AddAbstractParameterTicket (DependencyTicket ticket)
 Adds a ticket to the list of abstract parameter tickets. More...
 
void NoteTimeChanged (int64_t change_event)
 Notifies the local time tracker that time may have changed. More...
 
void NoteAccuracyChanged (int64_t change_event)
 Notifies the local accuracy tracker that the accuracy setting may have changed. More...
 
void NoteAllStateChanged (int64_t change_event)
 Notifies the local continuous, discrete, and abstract state trackers that each of them may have changed, likely because someone has asked to modify the whole state x. More...
 
void NoteAllContinuousStateChanged (int64_t change_event)
 Notifies the local q, v, and z trackers that each of them may have changed, likely because someone has asked to modify continuous state xc. More...
 
void NoteAllVZChanged (int64_t change_event)
 Notifies the local v and z trackers that each of them may have changed, likely because someone has asked to modify just the first-order state variables in xc. More...
 
void NoteAllQChanged (int64_t change_event)
 Notifies the local q tracker that the q's may have changed. More...
 
void NoteAllVChanged (int64_t change_event)
 Notifies the local v tracker that the v's may have changed. More...
 
void NoteAllZChanged (int64_t change_event)
 Notifies the local z tracker that the z's may have changed. More...
 
void NoteAllDiscreteStateChanged (int64_t change_event)
 Notifies each local discrete state group tracker that the value of the discrete state group it manages may have changed. More...
 
void NoteAllAbstractStateChanged (int64_t change_event)
 Notifies each local abstract state variable tracker that the value of the abstract state variable it manages may have changed. More...
 
void NoteAllParametersChanged (int64_t change_event)
 Notifies the local numeric and abstract parameter trackers that each of them may have changed, likely because someone asked to modify all the parameters. More...
 
void NoteAllNumericParametersChanged (int64_t change_event)
 Notifies each local numeric parameter tracker that the value of the parameter it manages may have changed. More...
 
void NoteAllAbstractParametersChanged (int64_t change_event)
 Notifies each local abstract parameter tracker that the value of the parameter it manages may have changed. More...
 

Static Protected Member Functions

static void PropagateTimeChange (Context< T > *context, const T &time, const std::optional< T > &true_time, int64_t change_event)
 (Internal use only) Sets a new time and notifies time-dependent quantities that they are now invalid, as part of a given change event. More...
 
static void PropagateAccuracyChange (Context< T > *context, const std::optional< double > &accuracy, int64_t change_event)
 (Internal use only) Sets a new accuracy and notifies accuracy-dependent quantities that they are now invalid, as part of a given change event. More...
 
static Parameters< T > & access_mutable_parameters (Context< T > *context)
 (Internal use only) Returns a reference to mutable parameters without invalidation notifications. More...
 
static State< T > & access_mutable_state (Context< T > *context)
 (Internal use only) Returns a reference to a mutable state without invalidation notifications. More...
 
static std::unique_ptr< Context< T > > CloneWithoutPointers (const Context< T > &source)
 (Internal use only) 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)
 (Internal use only) 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 PropagateBulkChange (ContextBase *context, int64_t change_event, void(ContextBase::*note_bulk_change)(int64_t change_event))
 (Internal use only) Applies the given bulk-change notification method to the given context, and propagates the notification to subcontexts if this is a DiagramContext. More...
 
static void set_parent (ContextBase *child, ContextBase *parent)
 Declares that parent is the context of the enclosing Diagram. More...
 

Constructor & Destructor Documentation

◆ Context() [1/3]

Context ( Context< T > &&  )
delete

◆ Context() [2/3]

Context ( )
protected

◆ Context() [3/3]

Context ( const Context< T > &  )
protected

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

◆ access_mutable_parameters()

static Parameters<T>& access_mutable_parameters ( Context< T > *  context)
staticprotected

(Internal use only) Returns a reference to mutable parameters without invalidation notifications.

Use get_mutable_parameters() instead for normal access.

◆ access_mutable_state()

static State<T>& access_mutable_state ( Context< T > *  context)
staticprotected

(Internal use only) Returns a reference to a mutable state without invalidation notifications.

Use get_mutable_state() instead for normal access.

◆ Clone()

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

Returns a deep copy of this Context.

Exceptions
std::exceptionif this is not the root context.

◆ CloneState()

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

Returns a deep copy of this Context's State.

◆ CloneWithoutPointers()

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

(Internal use only) Clones a context but without any of its internal pointers.

◆ do_access_mutable_state()

virtual State<T>& do_access_mutable_state ( )
protectedpure virtual

Returns a mutable reference to its concrete State object without any invalidation.

We promise not to allow user access to this object without invalidation.

◆ do_access_state()

virtual const State<T>& do_access_state ( ) const
protectedpure virtual

Returns a const reference to its concrete State object.

◆ do_to_string()

virtual std::string do_to_string ( ) const
protectedpure virtual

Returns a partial textual description of the Context, intended to be human-readable.

It is not guaranteed to be unambiguous nor complete.

◆ DoCloneState()

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

Returns the appropriate concrete State object to be returned by CloneState().

The implementation should not set_system_id on the result, the caller will set an id on the state after this method returns.

Implemented in LeafContext< T >.

◆ DoPropagateAccuracyChange()

virtual void DoPropagateAccuracyChange ( const std::optional< double > &  accuracy,
int64_t  change_event 
)
protectedvirtual

Invokes PropagateAccuracyChange() on all subcontexts of this Context.

The default implementation does nothing, which is suitable for leaf contexts. Diagram contexts must override.

◆ DoPropagateTimeChange()

virtual void DoPropagateTimeChange ( const T &  time_sec,
const std::optional< T > &  true_time,
int64_t  change_event 
)
protectedvirtual

Invokes PropagateTimeChange() on all subcontexts of this Context.

The default implementation does nothing, which is suitable for leaf contexts. Diagram contexts must override.

◆ FixInputPort()

FixedInputPortValue& FixInputPort

(Advanced) Connects the input port at index to a FixedInputPortValue with the given abstract value.

Returns a reference to the allocated FixedInputPortValue that 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.

This is the most general way to provide a value (type-erased) for an unconnected input port. Using the FixValue() method of the input port to set the value is the preferred workflow due to its additional sugar.

Note
Calling this method on an already connected input port, i.e., an input port that has previously been passed into a call to DiagramBuilder::Connect(), causes FixedInputPortValue to override any other value present on that port.
Precondition
index selects an existing input port of this Context.

◆ get_abstract_parameter()

const AbstractValue& get_abstract_parameter ( int  index) const

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

Precondition
index must identify an existing parameter.

◆ get_abstract_state() [1/2]

const AbstractValues& get_abstract_state ( ) const

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

◆ get_abstract_state() [2/2]

const U& get_abstract_state ( int  index) const

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

Precondition
index must identify an existing element.
the abstract state's type must match the template argument.

◆ get_accuracy()

const std::optional<double>& get_accuracy ( ) const

Returns the accuracy setting (if any).

Note that the return type is optional<double> rather than the double value itself.

See also
SetAccuracy() for details.

◆ get_continuous_state()

const ContinuousState<T>& get_continuous_state ( ) const

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

◆ get_continuous_state_vector()

const VectorBase<T>& get_continuous_state_vector ( ) const

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

The vector may be of size zero.

◆ get_discrete_state() [1/2]

const DiscreteValues<T>& get_discrete_state ( ) const

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

◆ get_discrete_state() [2/2]

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

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

Precondition
index must identify an existing group.

◆ get_discrete_state_vector()

const BasicVector<T>& get_discrete_state_vector ( ) const

Returns a reference to the only discrete state vector.

The vector may be of size zero.

Precondition
There is only one discrete state group.

◆ get_mutable_abstract_parameter()

AbstractValue& get_mutable_abstract_parameter ( int  index)

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

Sends out of date notifications for all computations dependent on this parameter.

Precondition
index must identify an existing abstract parameter.
Note
Currently notifies dependents of all abstract parameters.

◆ get_mutable_abstract_state() [1/2]

AbstractValues& get_mutable_abstract_state ( )

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

Sends out of date notifications for all abstract-state-dependent computations.

Warning
You must not use the returned reference to modify the size, number, or types of abstract state variables.

◆ get_mutable_abstract_state() [2/2]

U& get_mutable_abstract_state ( int  index)

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

Sends out of date notifications for all computations that depend on this abstract state variable.

Precondition
index must identify an existing element.
the abstract state's type must match the template argument.
Note
Currently notifies dependents of any abstract state variable.

◆ get_mutable_continuous_state()

ContinuousState<T>& get_mutable_continuous_state ( )

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

Sends out of date notifications for all continuous-state-dependent computations.

◆ get_mutable_continuous_state_vector()

VectorBase<T>& get_mutable_continuous_state_vector ( )

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

The vector may be of size zero. Sends out of date notifications for all continuous-state-dependent computations.

◆ get_mutable_discrete_state() [1/2]

DiscreteValues<T>& get_mutable_discrete_state ( )

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

Sends out of date notifications for all discrete-state-dependent computations.

Warning
You must not use the returned reference to modify the size or number of discrete state variables.

◆ get_mutable_discrete_state() [2/2]

BasicVector<T>& get_mutable_discrete_state ( int  index)

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

Sends out of date notifications for all computations that depend on this discrete state group.

Precondition
index must identify an existing group.
Note
Currently notifies dependents of all groups.

◆ get_mutable_discrete_state_vector()

BasicVector<T>& get_mutable_discrete_state_vector ( )

Returns a mutable reference to the only discrete state vector.

Sends out of date notifications for all discrete-state-dependent computations.

See also
get_discrete_state_vector().
Precondition
There is only one discrete state group.

◆ get_mutable_numeric_parameter()

BasicVector<T>& get_mutable_numeric_parameter ( int  index)

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

Sends out of date notifications for all computations dependent on this parameter.

Precondition
index must identify an existing numeric parameter.
Note
Currently notifies dependents of all numeric parameters.

◆ get_mutable_parameters()

Parameters<T>& get_mutable_parameters ( )

Returns a mutable reference to this Context's parameters.

Sends out of date notifications for all parameter-dependent computations. If you don't mean to change all the parameters, use the indexed methods to modify only some of the parameters so that fewer computations are invalidated and fewer notifications need be sent.

Warning
You must not use the returned reference to modify the size, number, or types of parameters.

◆ get_mutable_state()

State<T>& get_mutable_state ( )

Returns a mutable reference to the whole State, potentially invalidating all state-dependent computations so requiring out of date notifications to be made for all such computations.

If you don't mean to change the whole state, use more focused methods to modify only a portion of the state. See class documentation for more information.

Warning
You must not use the returned reference to modify the size, number, or types of state variables.

◆ get_numeric_parameter()

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

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

Precondition
index must identify an existing parameter.

◆ get_parameters()

const Parameters<T>& get_parameters ( ) const

Returns a const reference to this Context's parameters.

◆ get_state()

const State<T>& get_state ( ) const

Returns a const reference to the whole State.

◆ get_time()

const T& get_time ( ) const

Returns the current time in seconds.

See also
SetTime()

◆ GetMutableVZVectors()

std::pair<VectorBase<T>*, VectorBase<T>*> GetMutableVZVectors ( )

(Advanced) Returns mutable references to the first-order continuous state partitions v and z from xc.

Performs a single notification sweep to avoid duplicate notifications for computations that depend on both v and z. Does not invalidate computations that depend on time or pose q, unless those also depend on v or z.

See also
SetTimeAndGetMutableQVector()

◆ has_only_continuous_state()

bool has_only_continuous_state ( ) const

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

◆ has_only_discrete_state()

bool has_only_discrete_state ( ) const

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

◆ init_abstract_state()

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

(Internal use only) Sets the abstract state to xa, deleting whatever was there before.

Warning
Does not invalidate state-dependent computations.

◆ init_continuous_state()

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

(Internal use only) Sets the continuous state to xc, deleting whatever was there before.

Warning
Does not invalidate state-dependent computations.

◆ init_discrete_state()

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

(Internal use only) Sets the discrete state to xd, deleting whatever was there before.

Warning
Does not invalidate state-dependent computations.

◆ init_parameters()

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

(Internal use only) Sets the parameters to params, deleting whatever was there before.

You must supply a Parameters object; null is not acceptable.

Warning
Does not invalidate parameter-dependent computations.

◆ is_stateless()

bool is_stateless ( ) const

Returns true if the Context has no state.

◆ NoteContinuousStateChange()

void NoteContinuousStateChange ( )

(Advanced) Registers an intention to modify the continuous state xc.

Intended use is for integrators that are already holding a mutable reference to xc which they are going to modify. Performs a notification sweep to invalidate computations that depend on any continuous state variables. If you need to change the time also, use SetTimeAndNoteContinuousStateChange() instead to avoid unnecessary duplicate notifications.

See also
SetTimeAndNoteContinuousStateChange()

◆ num_abstract_parameters()

int num_abstract_parameters ( ) const

Returns the number of abstract-valued parameters.

◆ num_abstract_states()

int num_abstract_states ( ) const

Returns the number of elements in the abstract state.

◆ num_continuous_states()

int num_continuous_states ( ) const

Returns the number of continuous state variables xc = {q, v, z}.

◆ num_discrete_state_groups()

int num_discrete_state_groups ( ) const

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

◆ num_numeric_parameter_groups()

int num_numeric_parameter_groups ( ) const

Returns the number of vector-valued parameters.

◆ num_total_states()

int num_total_states ( ) const

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

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

◆ operator=() [1/2]

Context& operator= ( const Context< T > &  )
delete

◆ operator=() [2/2]

Context& operator= ( Context< T > &&  )
delete

◆ PropagateAccuracyChange()

static void PropagateAccuracyChange ( Context< T > *  context,
const std::optional< double > &  accuracy,
int64_t  change_event 
)
staticprotected

(Internal use only) Sets a new accuracy and notifies accuracy-dependent quantities that they are now invalid, as part of a given change event.

◆ PropagateTimeChange()

static void PropagateTimeChange ( Context< T > *  context,
const T &  time,
const std::optional< T > &  true_time,
int64_t  change_event 
)
staticprotected

(Internal use only) Sets a new time and notifies time-dependent quantities that they are now invalid, as part of a given change event.

◆ SetAbstractState()

void SetAbstractState ( int  index,
const ValueType &  value 
)

Sets the value of the abstract state variable selected by index.

Sends out of date notifications for all computations that depend on that abstract state variable. The template type will be inferred and need not be specified explicitly.

Precondition
index must identify an existing abstract state variable.
the abstract state's type must match the template argument.
Note
Currently notifies dependents of any abstract state variable.

◆ SetAccuracy()

void SetAccuracy ( const std::optional< double > &  accuracy)

Records the user's requested accuracy, which is a unit-less quantity designed for use with simulation and other numerical studies.

Since accuracy is unit-less, algorithms and systems are free to interpret this quantity as they wish. The intention is that more computational work is acceptable as the accuracy setting is tightened (set closer to zero). If no accuracy is requested, computations are free to choose suitable defaults, or to refuse to proceed without an explicit accuracy setting. 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 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.

Any accuracy-dependent computation in this Context and its subcontexts may be invalidated by a change to the accuracy setting, so out of date notifications are sent to all such computations (at least if the accuracy setting has actually changed). Accuracy must have the same value in every subcontext within the same context tree so may only be modified at the root context of a tree.

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 notify accuracy-dependent cached results that they are out of date when the accuracy setting changes.
Exceptions
std::exceptionif this is not the root context.

◆ SetContinuousState()

void SetContinuousState ( const Eigen::Ref< const VectorX< T >> &  xc)

Sets the continuous state to xc, including q, v, and z partitions.

The supplied vector must be the same size as the existing continuous state. Sends out of date notifications for all continuous-state-dependent computations.

◆ SetDiscreteState() [1/3]

void SetDiscreteState ( const Eigen::Ref< const VectorX< T >> &  xd)

Sets the discrete state to xd, assuming there is just one discrete state group.

The supplied vector must be the same size as the existing discrete state. Sends out of date notifications for all discrete-state-dependent computations. Use the other signature for this method if you have multiple discrete state groups.

Precondition
There is exactly one discrete state group.

◆ SetDiscreteState() [2/3]

void SetDiscreteState ( int  group_index,
const Eigen::Ref< const VectorX< T >> &  xd 
)

Sets the discrete state group indicated by group_index to xd.

The supplied vector xd must be the same size as the existing discrete state group. Sends out of date notifications for all computations that depend on this discrete state group.

Precondition
group_index identifies an existing group.
Note
Currently notifies dependents of all groups.

◆ SetDiscreteState() [3/3]

void SetDiscreteState ( const DiscreteValues< T > &  xd)

Sets all the discrete state variables in this Context from a compatible DiscreteValues object.

Exceptions
std::exceptionunless the number of groups and size of each group of xd matches those in this Context.

◆ SetStateAndParametersFrom()

void SetStateAndParametersFrom ( const Context< U > &  source)

Copies all state and parameters in source, where numerical values are of type U, to this context.

Time and accuracy are unchanged in this context, which means that this method can be called on a subcontext. Sends out of date notifications for all dependent computations in this context.

Note
Currently does not copy fixed input port values from source. See System::FixInputPortsFrom() if you want to copy those.
See also
SetTimeStateAndParametersFrom() if you want to copy time and accuracy along with state and parameters to a root context.

◆ SetTime()

void SetTime ( const T &  time_sec)

Sets the current time in seconds.

Sends out of date notifications for all time-dependent computations (at least if the time has actually changed). Time must have the same value in every subcontext within the same Diagram context tree so may only be modified at the root context of the tree.

Exceptions
std::exceptionif this is not the root context.

◆ SetTimeAndContinuousState()

void SetTimeAndContinuousState ( const T &  time_sec,
const Eigen::Ref< const VectorX< T >> &  xc 
)

Sets time to time_sec and continuous state to xc.

Performs a single notification sweep to avoid duplicate notifications for computations that depend on both time and state.

Exceptions
std::exceptionif this is not the root context.

◆ SetTimeAndGetMutableContinuousStateVector()

VectorBase<T>& SetTimeAndGetMutableContinuousStateVector ( const T &  time_sec)

(Advanced) Sets time and returns a mutable reference to the continuous state xc (including q, v, z) as a VectorBase.

Performs a single notification sweep to avoid duplicate notifications for computations that depend on both time and state.

Exceptions
std::exceptionif this is not the root context.
See also
SetTimeAndNoteContinuousStateChange()
SetTimeAndGetMutableContinuousState()

◆ SetTimeAndGetMutableQVector()

VectorBase<T>& SetTimeAndGetMutableQVector ( const T &  time_sec)

(Advanced) Sets time and returns a mutable reference to the second-order continuous state partition q from xc.

Performs a single notification sweep to avoid duplicate notifications for computations that depend on both time and q.

Exceptions
std::exceptionif this is not the root context.
See also
GetMutableVZVectors()
SetTimeAndGetMutableContinuousStateVector()

◆ SetTimeAndNoteContinuousStateChange()

void SetTimeAndNoteContinuousStateChange ( const T &  time_sec)

(Advanced) Sets time and registers an intention to modify the continuous state xc.

Intended use is for integrators that are already holding a mutable reference to xc which they are going to modify. Performs a single notification sweep to avoid duplicate notifications for computations that depend on both time and state.

Exceptions
std::exceptionif this is not the root context.
See also
SetTimeAndGetMutableContinuousStateVector()

◆ SetTimeStateAndParametersFrom()

void SetTimeStateAndParametersFrom ( const Context< U > &  source)

Copies time, accuracy, all state and all parameters in source, where numerical values are of type U, to this context.

This method can only be called on root contexts because time and accuracy are copied. Sends out of date notifications for all dependent computations in this context.

Exceptions
std::exceptionif this is not the root context.
Note
Currently does not copy fixed input port values from source. See System::FixInputPortsFrom() if you want to copy those.
See also
SetStateAndParametersFrom() if you want to copy state and parameters to a non-root context.

◆ to_string()

std::string to_string ( ) const

Returns a partial textual description of the Context, intended to be human-readable.

It is not guaranteed to be unambiguous nor complete.


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