Drake
ContextBase Class Referenceabstract

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

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

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

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

Friends

class detail::SystemBaseContextBaseAttorney
 

Detailed Description

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

That includes caching and 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.

Constructor & Destructor Documentation

ContextBase ( ContextBase &&  )
delete
~ContextBase ( )
override
ContextBase ( )
inlineprotected

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

void AddInputPort ( InputPortIndex  expected_index,
DependencyTicket  ticket 
)
protected

Adds the next input port.

Expected index is supplied along with the assigned ticket. Subscribes the "all input ports" tracker to this one.

Here is the call graph for this function:

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.

Here is the call graph for this function:

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.

Here is the call graph for this function:

Here is the caller graph for this function:

std::unique_ptr< ContextBase > Clone ( ) const

Creates an identical copy of the concrete context object.

Here is the call graph for this function:

Here is the caller graph for this function:

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

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

Here is the call graph for this function:

Here is the caller graph for this function:

void DisableCaching ( ) const
inline

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

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

Here is the call graph for this function:

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 unique_ptr<ContextBase>(new DerivedType(*this));.

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

Here is the caller graph for this function:

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

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

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

Here is the call graph for this function:

Here is the caller graph for this function:

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

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.

Here is the call graph for this function:

Here is the caller graph for this function:

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

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

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

Here is the call graph for this function:

void EnableCaching ( ) const
inline

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

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.

Here is the call graph for this function:

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.

Here is the call graph for this function:

Here is the caller graph for this function:

FixedInputPortValue & FixInputPort ( int  index,
std::unique_ptr< AbstractValue value 
)

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. See Context<T> for more-convenient overloads of FixInputPort() for vector values with elements of type T.

Precondition
index selects an existing input port of this Context.

Here is the caller graph for this function:

FixedInputPortValue& FixInputPort ( int  index,
const AbstractValue value 
)
inline

Same as above method but the value is passed by const reference instead of by unique_ptr.

The port will contain a copy of the value (not retain a pointer to the value).

Here is the call graph for this function:

const Cache& get_cache ( ) const
inline

Returns a const reference to this subcontext's cache.

Here is the caller graph for this function:

const DependencyGraph& get_dependency_graph ( ) const
inline

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.

Here is the caller graph for this function:

Cache& get_mutable_cache ( ) const
inline

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

Here is the caller graph for this function:

DependencyGraph& get_mutable_dependency_graph ( )
inline

Returns a mutable reference to the dependency graph.

Here is the caller graph for this function:

DependencyTracker& get_mutable_tracker ( DependencyTicket  ticket)
inline

Returns a mutable reference to a DependencyTracker in this subcontext.

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

Here is the caller graph for this function:

int get_num_input_ports ( ) const
inline

Returns the number of input ports in this context.

Here is the caller graph for this function:

int get_num_output_ports ( ) const
inline

Returns the number of output ports represented in this context.

Here is the caller graph for this function:

const DependencyTracker& get_tracker ( DependencyTicket  ticket) const
inline

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.

const std::string& GetSystemName ( ) const
inlinefinal

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.

Here is the caller graph for this function:

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.

Here is the call graph for this function:

Here is the caller graph for this function:

DependencyTicket input_port_ticket ( InputPortIndex  port_num)
inline

Returns the dependency ticket associated with a particular input port.

Here is the caller graph for this function:

const FixedInputPortValue* MaybeGetFixedInputPortValue ( int  index) const
inline

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.

Here is the caller graph for this function:

FixedInputPortValue* MaybeGetMutableFixedInputPortValue ( int  index)
inline

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.
ContextBase& operator= ( const ContextBase )
delete
ContextBase& operator= ( ContextBase &&  )
delete
DependencyTicket output_port_ticket ( OutputPortIndex  port_num)
inline

Returns the dependency ticket associated with a particular output port.

Here is the caller graph for this function:

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

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

Here is the call graph for this function:

static void set_parent ( ContextBase child,
const ContextBase parent 
)
inlinestaticprotected

Declares that parent is the context of the enclosing Diagram.

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

Here is the call graph for this function:

Here is the caller graph for this function:

void SetAllCacheEntriesOutOfDate ( ) const
inline

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

Here is the call graph for this function:

Friends And Related Function Documentation

friend class detail::SystemBaseContextBaseAttorney
friend

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