Drake
Drake C++ Documentation
ContextBase Class Referenceabstract

Detailed Description

Provides non-templatized Context functionality shared by the templatized derived classes.

That includes caching, dependency tracking, and management of local values for fixed input ports.

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.

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

Public Member Functions

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...
 
Does not allow copy, move, or assignment.
 ContextBase (ContextBase &&)=delete
 
ContextBaseoperator= (const ContextBase &)=delete
 
ContextBaseoperator= (ContextBase &&)=delete
 

Protected Member Functions

 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...
 
Add dependency tracking resources (Internal use only)

Methods in this group are used by SystemBase and unit testing while creating a Context that can track dependencies for a given System.

Although these methods are protected, SystemBase is granted permission to invoke them (via an attorney class).

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...
 
Change notification methods (Internal use only)

These "Note" methods are used by framework-internal derived classes to effect change notifications that propagate down from a DiagramContext (where the change is initiated) through all its subcontexts, recursively.

Such notification sweeps result in the "out of date" flag being set in each of the affected cache entry values. Each of these "Note" methods affects only the local context, but all have identical signatures so can be passed down the context tree to operate on every subcontext. The change_event argument should be the result of the start_new_change_event() method.

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

Friends

class internal::SystemBaseContextBaseAttorney
 

Constructor & Destructor Documentation

◆ ContextBase() [1/3]

ContextBase ( ContextBase &&  )
delete

◆ ~ContextBase()

~ContextBase ( )
override

◆ ContextBase() [2/3]

ContextBase ( )
protected

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

We can't allocate trackers for individual discrete & abstract states, parameters, or input ports since we don't yet know how many there are.

◆ ContextBase() [3/3]

ContextBase ( const ContextBase )
protecteddefault

Copy constructor takes care of base class data members, but does not fix up base class pointers.

Derived classes must implement copy constructors that delegate to this one for use in their DoCloneWithoutPointers() implementations. The cache and dependency graph are copied, but any pointers contained in the source are left null in the copy.

Member Function Documentation

◆ AddAbstractParameterTicket()

void AddAbstractParameterTicket ( DependencyTicket  ticket)
protected

Adds a ticket to the list of abstract parameter tickets.

◆ AddAbstractStateTicket()

void AddAbstractStateTicket ( DependencyTicket  ticket)
protected

Adds a ticket to the list of abstract state tickets.

◆ AddDiscreteStateTicket()

void AddDiscreteStateTicket ( DependencyTicket  ticket)
protected

Adds a ticket to the list of discrete state tickets.

◆ AddInputPort()

void AddInputPort ( InputPortIndex  expected_index,
DependencyTicket  ticket,
std::function< void(const AbstractValue &)>  fixed_input_type_checker 
)
protected

Adds the next input port.

Expected index is supplied along with the assigned ticket. Subscribes the "all input ports" tracker to this one. The fixed_input_type_checker will be used for validation when setting a fixed input, or may be null when no validation should be performed. Typically the fixed_input_type_checker is created by System::MakeFixInputPortTypeChecker. The fixed_input_type_checker lifetime will be the same as this ContextBase, so it should not depend on pointers that may go out of scope. Most acutely, the function must not depend on any captured SystemBase pointers.

◆ AddNumericParameterTicket()

void AddNumericParameterTicket ( DependencyTicket  ticket)
protected

Adds a ticket to the list of numeric parameter tickets.

◆ AddOutputPort()

void AddOutputPort ( OutputPortIndex  expected_index,
DependencyTicket  ticket,
const internal::OutputPortPrerequisite &  prerequisite 
)
protected

Adds the next output port.

Expected index is supplied along with the assigned ticket.

◆ BuildTrackerPointerMap()

static void BuildTrackerPointerMap ( const ContextBase source,
const ContextBase clone,
DependencyTracker::PointerMap tracker_map 
)
staticprotected

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

This must be done for the whole Context tree because pointers can point outside of their containing subcontext.

◆ Clone()

std::unique_ptr<ContextBase> Clone ( ) const

Creates an identical copy of the concrete context object.

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

◆ CloneWithoutPointers()

static std::unique_ptr<ContextBase> CloneWithoutPointers ( const ContextBase source)
staticprotected

(Internal use only) Clones a context but without copying any of its internal pointers; the clone's pointers are set to null.

◆ DisableCaching()

void DisableCaching ( ) const

(Debugging) Disables caching recursively for this context and all its subcontexts.

Caching is enabled by default. Disabling forces every Eval() method to perform a full calculation rather than returning the cached one. Results should be identical with or without caching, except for performance. If they are not, there is likely a problem with (a) the specified dependencies for some calculation, or (b) a misuse of references into cached values that hides modifications from the caching system, or (c) a bug in the caching system. The is_disabled flags are independent of the out_of_date flags, which continue to be maintained even when caching is disabled (though they are ignored). Caching can be re-enabled using EnableCaching().

◆ DoCloneWithoutPointers()

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

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.

To do that, implement a protected copy constructor that inherits from the base class copy constructor (which doesn't repair the pointers), then implement DoCloneWithoutPointers() as return std::unique_ptr<ContextBase>(new DerivedType(*this));.

Implemented in LeafContext< T >.

◆ DoPropagateBuildTrackerPointerMap()

virtual void DoPropagateBuildTrackerPointerMap ( const ContextBase clone,
DependencyTracker::PointerMap tracker_map 
) const
protectedvirtual

DiagramContext must implement this to invoke BuildTrackerPointerMap() on each of its subcontexts.

The default implementation does nothing which is fine for a LeafContext.

◆ DoPropagateBulkChange()

virtual void DoPropagateBulkChange ( int64_t  change_event,
void(ContextBase::*)(int64_t change_event)  note_bulk_change 
)
protectedvirtual

DiagramContext must implement this to invoke PropagateBulkChange() on its subcontexts, passing along the indicated method that specifies the particular bulk change (e.g.

whole state, all parameters, all discrete state variables, etc.). The default implementation does nothing which is fine for a LeafContext.

◆ DoPropagateCachingChange()

virtual void DoPropagateCachingChange ( void(Cache::*)()  caching_change) const
protectedvirtual

DiagramContext must implement this to invoke a caching behavior change on each of its subcontexts.

The default implementation does nothing which is fine for a LeafContext.

◆ DoPropagateFixContextPointers()

virtual void DoPropagateFixContextPointers ( const ContextBase source,
const DependencyTracker::PointerMap tracker_map 
)
protectedvirtual

DiagramContext must implement this to invoke FixContextPointers() on each of its subcontexts.

The default implementation does nothing which is fine for a LeafContext.

◆ EnableCaching()

void EnableCaching ( ) const

(Debugging) Re-enables caching recursively for this context and all its subcontexts.

Caching is enabled by default but may have been disabled via a call to DisableCaching(). The is_disabled flags are independent of the out_of_date flags, which continue to be maintained even when caching is disabled (though they are ignored). Hence re-enabling the cache with this method may result in some entries being already considered up to date. See SetAllCacheEntriesOutOfDate() if you want to ensure that caching restarts with everything out of date. You might want to do that, for example, for repeatability or because you modified something in the debugger and want to make sure it gets used.

◆ FixContextPointers()

static void FixContextPointers ( const ContextBase source,
const DependencyTracker::PointerMap tracker_map,
ContextBase clone 
)
staticprotected

(Internal use only) Assuming clone is a recently-cloned Context that has yet to have its internal pointers updated, sets those pointers now.

The given map is used to update tracker pointers.

◆ FixInputPort()

FixedInputPortValue& FixInputPort ( int  index,
const AbstractValue value 
)

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

◆ FreezeCache()

void FreezeCache ( ) const

(Advanced) Freezes the cache at its current contents, preventing any further cache updates.

When frozen, accessing an out-of-date cache entry causes an exception to be throw. This is applied recursively to this Context and all its subcontexts, but not to its parent or siblings so it is most useful when called on the root Context. If the cache was already frozen this method does nothing but waste a little time.

◆ get_cache()

const Cache& get_cache ( ) const

Returns a const reference to this subcontext's cache.

◆ get_dependency_graph()

const DependencyGraph& get_dependency_graph ( ) const

Returns a const reference to the collection of value trackers within this subcontext.

Together these form the dependency subgraph for the values in this subcontext, plus edges leading to neighboring trackers.

◆ get_mutable_cache()

Cache& get_mutable_cache ( ) const

(Advanced) Returns a mutable reference to this subcontext's cache.

Note that this method is const because the cache is always writable.

Warning
Writing directly to the cache does not automatically propagate invalidations to downstream dependents of a contained cache entry, because invalidations would normally have been propagated when the cache entry itself went out of date. Cache entries are updated automatically when needed via their Calc() methods; most users should not bypass that mechanism by using this method.

◆ get_mutable_dependency_graph()

DependencyGraph& get_mutable_dependency_graph ( )

Returns a mutable reference to the dependency graph.

◆ get_mutable_tracker()

DependencyTracker& get_mutable_tracker ( DependencyTicket  ticket)

Returns a mutable reference to a DependencyTracker in this subcontext.

(You do not need mutable access just to issue value change notifications.)

◆ get_system_id()

internal::SystemId get_system_id ( ) const

(Internal) Gets the id of the subsystem that created this context.

For more information, see System Compatibility.

◆ get_tracker()

const DependencyTracker& get_tracker ( DependencyTicket  ticket) const

Returns a const reference to a DependencyTracker in this subcontext.

Advanced users and internal code can use the returned reference to issue value change notifications – mutable access is not required for that purpose.

◆ GetSystemName()

const std::string& GetSystemName ( ) const
final

Returns the local name of the subsystem for which this is the Context.

This is intended primarily for error messages and logging.

See also
SystemBase::GetSystemName() for details.
GetSystemPathname() if you want the full name.

◆ GetSystemPathname()

std::string GetSystemPathname ( ) const
final

Returns the full pathname of the subsystem for which this is the Context.

This is intended primarily for error messages and logging.

See also
SystemBase::GetSystemPathname() for details.

◆ input_port_ticket()

DependencyTicket input_port_ticket ( InputPortIndex  port_num)

Returns the dependency ticket associated with a particular input port.

◆ is_cache_frozen()

bool is_cache_frozen ( ) const
final

(Advanced) Reports whether this Context's cache is currently frozen.

This checks only locally; it is possible that parent, child, or sibling subcontext caches are in a different state than this one.

◆ is_root_context()

bool is_root_context ( ) const

Returns true if this context has no parent.

◆ MaybeGetFixedInputPortValue()

const FixedInputPortValue* MaybeGetFixedInputPortValue ( int  index) const

For input port index, returns a const FixedInputPortValue if the port is fixed, otherwise nullptr.

Precondition
index selects an existing input port of this Context.

◆ MaybeGetMutableFixedInputPortValue()

FixedInputPortValue* MaybeGetMutableFixedInputPortValue ( int  index)

For input port index, returns a mutable FixedInputPortValue if the port is fixed, otherwise nullptr.

Precondition
index selects an existing input port of this Context.

◆ NoteAccuracyChanged()

void NoteAccuracyChanged ( int64_t  change_event)
protected

Notifies the local accuracy tracker that the accuracy setting may have changed.

◆ NoteAllAbstractParametersChanged()

void NoteAllAbstractParametersChanged ( int64_t  change_event)
protected

Notifies each local abstract parameter tracker that the value of the parameter it manages may have changed.

If there are no abstract parameters owned by this context, nothing happens. A DiagramContext does not own any parameters.

◆ NoteAllAbstractStateChanged()

void NoteAllAbstractStateChanged ( int64_t  change_event)
protected

Notifies each local abstract state variable tracker that the value of the abstract state variable it manages may have changed.

If there are no abstract state variables owned by this context, nothing happens. A DiagramContext does not own any abstract state variables.

◆ NoteAllContinuousStateChanged()

void NoteAllContinuousStateChanged ( int64_t  change_event)
protected

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.

◆ NoteAllDiscreteStateChanged()

void NoteAllDiscreteStateChanged ( int64_t  change_event)
protected

Notifies each local discrete state group tracker that the value of the discrete state group it manages may have changed.

If there are no discrete state groups owned by this context, nothing happens. A DiagramContext does not own any discrete state groups.

◆ NoteAllNumericParametersChanged()

void NoteAllNumericParametersChanged ( int64_t  change_event)
protected

Notifies each local numeric parameter tracker that the value of the parameter it manages may have changed.

If there are no numeric parameters owned by this context, nothing happens. A DiagramContext does not own any parameters.

◆ NoteAllParametersChanged()

void NoteAllParametersChanged ( int64_t  change_event)
protected

Notifies the local numeric and abstract parameter trackers that each of them may have changed, likely because someone asked to modify all the parameters.

◆ NoteAllQChanged()

void NoteAllQChanged ( int64_t  change_event)
protected

Notifies the local q tracker that the q's may have changed.

◆ NoteAllStateChanged()

void NoteAllStateChanged ( int64_t  change_event)
protected

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.

◆ NoteAllVChanged()

void NoteAllVChanged ( int64_t  change_event)
protected

Notifies the local v tracker that the v's may have changed.

◆ NoteAllVZChanged()

void NoteAllVZChanged ( int64_t  change_event)
protected

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.

◆ NoteAllZChanged()

void NoteAllZChanged ( int64_t  change_event)
protected

Notifies the local z tracker that the z's may have changed.

◆ NoteTimeChanged()

void NoteTimeChanged ( int64_t  change_event)
protected

Notifies the local time tracker that time may have changed.

◆ num_input_ports()

int num_input_ports ( ) const

Returns the number of input ports in this context.

◆ num_output_ports()

int num_output_ports ( ) const

Returns the number of output ports represented in this context.

◆ operator=() [1/2]

ContextBase& operator= ( const ContextBase )
delete

◆ operator=() [2/2]

ContextBase& operator= ( ContextBase &&  )
delete

◆ output_port_ticket()

DependencyTicket output_port_ticket ( OutputPortIndex  port_num)

Returns the dependency ticket associated with a particular output port.

◆ owns_any_variables_or_parameters()

bool owns_any_variables_or_parameters ( ) const
protected

(Internal use only) Returns true if this context provides resources for its own individual state variables or parameters.

That means those variables or parameters were declared by this context's corresponding System. Currently only leaf systems may declare variables and parameters; diagram contexts can use this method to check that invariant.

◆ PropagateBulkChange() [1/2]

static void PropagateBulkChange ( ContextBase context,
int64_t  change_event,
void(ContextBase::*)(int64_t change_event)  note_bulk_change 
)
staticprotected

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

◆ PropagateBulkChange() [2/2]

void PropagateBulkChange ( int64_t  change_event,
void(ContextBase::*)(int64_t change_event)  note_bulk_change 
)
protected

(Internal use only) This is a convenience method for invoking the eponymous static method on this context (which occurs frequently).

◆ PropagateCachingChange()

static void PropagateCachingChange ( const ContextBase context,
void(Cache::*)()  caching_change 
)
staticprotected

(Internal use only) Applies the given caching-change notification method to context, and propagates the notification to subcontexts if context is a DiagramContext.

Used, for example, to enable and disable the cache. The supplied context is const so depends on the cache being mutable.

◆ set_parent()

static void set_parent ( ContextBase child,
ContextBase parent 
)
staticprotected

Declares that parent is the context of the enclosing Diagram.

Aborts if the parent has already been set or is null.

◆ SetAllCacheEntriesOutOfDate()

void SetAllCacheEntriesOutOfDate ( ) const

(Debugging) Marks all cache entries out of date, recursively for this context and all its subcontexts.

This forces the next Eval() request for each cache entry to perform a full calculation rather than returning the cached one. After that first recalculation, normal caching behavior resumes (assuming the cache is not disabled). Results should be identical whether this is called or not, since the caching system should be maintaining this flag correctly. If they are not, see the documentation for SetIsCacheDisabled() for suggestions.

◆ start_new_change_event()

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.

This number is not reset after a Context is copied but continues to count up.

◆ UnfreezeCache()

void UnfreezeCache ( ) const

(Advanced) Unfreezes the cache if it was previously frozen.

This is applied recursively to this Context and all its subcontexts, but not to its parent or siblings. If the cache was not frozen, this does nothing but waste a little time.

Friends And Related Function Documentation

◆ internal::SystemBaseContextBaseAttorney

friend class internal::SystemBaseContextBaseAttorney
friend

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