Drake
context_base.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <algorithm>
4 #include <cstdint>
5 #include <memory>
6 #include <string>
7 #include <utility>
8 #include <vector>
9 
11 #include "drake/common/unused.h"
16 
17 namespace drake {
18 namespace systems {
19 
20 #ifndef DRAKE_DOXYGEN_CXX
21 namespace detail {
22 // This provides SystemBase limited "friend" access to ContextBase.
23 class SystemBaseContextBaseAttorney;
24 } // namespace detail
25 #endif
26 
27 /** Provides non-templatized functionality shared by the templatized derived
28 classes. That includes caching and dependency tracking, and management of
29 local values for fixed input ports.
30 
31 Terminology: in general a Drake System is a tree structure composed of
32 "subsystems", which are themselves System objects. The corresponding Context is
33 a parallel tree structure composed of "subcontexts", which are themselves
34 Context objects. There is a one-to-one correspondence between subsystems and
35 subcontexts. Within a given System (Context), its child subsystems (subcontexts)
36 are indexed using a SubsystemIndex; there is no separate SubcontextIndex since
37 the numbering must be identical. */
38 class ContextBase : public internal::ContextMessageInterface {
39  public:
40  /** @name Does not allow copy, move, or assignment. */
41  /** @{ */
42  // Copy constructor is used only to facilitate implementation of Clone()
43  // in derived classes.
44  ContextBase(ContextBase&&) = delete;
45  ContextBase& operator=(const ContextBase&) = delete;
46  ContextBase& operator=(ContextBase&&) = delete;
47  /** @} */
48 
49  /** Creates an identical copy of the concrete context object. */
50  std::unique_ptr<ContextBase> Clone() const;
51 
52  ~ContextBase() override;
53 
54  /** (Debugging) Disables caching recursively for this context
55  and all its subcontexts. Disabling forces every `Eval()` method to perform a
56  full calculation rather than returning the cached one. Results should be
57  identical with or without caching, except for performance. If they are not,
58  there is likely a problem with (a) the specified dependencies for some
59  calculation, or (b) a misuse of references into cached values that hides
60  modifications from the caching system, or (c) a bug in the caching system. The
61  `is_disabled` flags are independent of the `out_of_date` flags, which continue
62  to be maintained even when caching is disabled (though they are ignored). */
63  void DisableCaching() const {
64  PropagateCachingChange(*this, &Cache::DisableCaching);
65  }
66 
67  /** (Debugging) Re-enables caching recursively for this context and all its
68  subcontexts. The `is_disabled` flags are independent of the `out_of_date`
69  flags, which continue to be maintained even when caching is disabled (though
70  they are ignored). Hence re-enabling the cache with this method may result in
71  some entries being already considered up to date. See
72  SetAllCacheEntriesOutOfDate() if you want to ensure that caching restarts with
73  everything out of date. You might want to do that, for example, for
74  repeatability or because you modified something in the debugger and want to
75  make sure it gets used. */
76  void EnableCaching() const {
77  PropagateCachingChange(*this, &Cache::EnableCaching);
78  }
79 
80  /** (Debugging) Marks all cache entries out of date, recursively for this
81  context and all its subcontexts. This forces the next `Eval()` request for
82  each cache entry to perform a full calculation rather than returning the
83  cached one. After that first recalculation, normal caching behavior resumes
84  (assuming the cache is not disabled). Results should be identical whether this
85  is called or not, since the caching system should be maintaining this flag
86  correctly. If they are not, see the documentation for SetIsCacheDisabled() for
87  suggestions. */
89  PropagateCachingChange(*this, &Cache::SetAllEntriesOutOfDate);
90  }
91 
92  /** Returns the local name of the subsystem for which this is the Context.
93  This is intended primarily for error messages and logging.
94  @see SystemBase::GetSystemName() for details.
95  @see GetSystemPathname() if you want the full name. */
96  const std::string& GetSystemName() const final {
97  return system_name_.empty() ? internal::SystemMessageInterface::no_name()
98  : system_name_;
99  }
100 
101  /** Returns the full pathname of the subsystem for which this is the Context.
102  This is intended primarily for error messages and logging.
103  @see SystemBase::GetSystemPathname() for details. */
104  std::string GetSystemPathname() const final;
105 
106  /** Returns a const reference to this subcontext's cache. */
107  const Cache& get_cache() const {
108  return cache_;
109  }
110 
111  /** (Advanced) Returns a mutable reference to this subcontext's cache. Note
112  that this method is const because the cache is always writable.
113  @warning Writing directly to the cache does not automatically propagate
114  invalidations to downstream dependents of a contained cache entry, because
115  invalidations would normally have been propagated when the cache entry itself
116  went out of date. Cache entries are updated automatically when needed via
117  their `Calc()` methods; most users should not bypass that mechanism by using
118  this method. */
120  return cache_;
121  }
122 
123  /** Returns a const reference to a DependencyTracker in this subcontext.
124  Advanced users and internal code can use the returned reference to issue value
125  change notifications -- mutable access is not required for that purpose. */
127  return graph_.get_tracker(ticket);
128  }
129 
130  /** Returns a mutable reference to a DependencyTracker in this subcontext.
131  (You do not need mutable access just to issue value change notifications.) */
133  return graph_.get_mutable_tracker(ticket);
134  }
135 
136  /** Returns a const reference to the collection of value trackers within
137  this subcontext. Together these form the dependency subgraph for the values
138  in this subcontext, plus edges leading to neighboring trackers. */
140  return graph_;
141  }
142 
143  /** Returns a mutable reference to the dependency graph. */
145  return graph_;
146  }
147 
148  /** Returns the number of input ports in this context. */
149  int get_num_input_ports() const {
150  DRAKE_ASSERT(input_port_tickets_.size() == input_port_values_.size());
151  return static_cast<int>(input_port_tickets_.size());
152  }
153 
154  /** Returns the number of output ports represented in this context. */
155  int get_num_output_ports() const {
156  return static_cast<int>(output_port_tickets_.size());
157  }
158 
159  /** Returns the dependency ticket associated with a particular input port. */
161  DRAKE_DEMAND(port_num < get_num_input_ports());
162  return input_port_tickets_[port_num];
163  }
164 
165  /** Returns the dependency ticket associated with a particular output port. */
167  DRAKE_DEMAND(port_num < get_num_output_ports());
168  return output_port_tickets_[port_num];
169  }
170 
171  /** Connects the input port at `index` to a FixedInputPortValue with
172  the given abstract `value`. Returns a reference to the allocated
173  FixedInputPortValue that will remain valid until this input port's value
174  source is replaced or the Context is destroyed. You may use that reference to
175  modify the input port's value using the appropriate FixedInputPortValue
176  method, which will ensure that invalidation notifications are delivered.
177 
178  This is the most general way to provide a value (type-erased) for an
179  unconnected input port. See `Context<T>` for more-convenient overloads of
180  FixInputPort() for vector values with elements of type T.
181 
182  @pre `index` selects an existing input port of this Context. */
183  FixedInputPortValue& FixInputPort(
184  int index, std::unique_ptr<AbstractValue> value);
185 
186  /** Same as above method but the value is passed by const reference instead
187  of by unique_ptr. The port will contain a copy of the `value` (not retain a
188  pointer to the `value`). */
189  FixedInputPortValue& FixInputPort(int index, const AbstractValue& value) {
190  return FixInputPort(index, value.Clone());
191  }
192 
193  /** For input port `index`, returns a const FixedInputPortValue if the port is
194  fixed, otherwise nullptr.
195  @pre `index` selects an existing input port of this Context. */
197  DRAKE_DEMAND(0 <= index && index < get_num_input_ports());
198  return input_port_values_[index].get();
199  }
200 
201  /** For input port `index`, returns a mutable FixedInputPortValue if the port
202  is fixed, otherwise nullptr.
203  @pre `index` selects an existing input port of this Context. */
205  DRAKE_DEMAND(0 <= index && index < get_num_input_ports());
206  return input_port_values_[index].get_mutable();
207  }
208 
209  protected:
210  /** Default constructor creates an empty ContextBase but initializes all the
211  built-in dependency trackers that are the same in every System (like time,
212  q, all states, all inputs, etc.). We can't allocate trackers for individual
213  discrete & abstract states, parameters, or input ports since we don't yet
214  know how many there are. */
215  ContextBase() : cache_(this), graph_(this) {
216  CreateBuiltInTrackers();
217  }
218 
219  /** Copy constructor takes care of base class data members, but _does not_ fix
220  up base class pointers. Derived classes must implement copy constructors that
221  delegate to this one for use in their DoCloneWithoutPointers()
222  implementations. The cache and dependency graph are copied, but any pointers
223  contained in the source are left null in the copy. */
224  ContextBase(const ContextBase&) = default;
225 
226  /** Adds the next input port. Expected index is supplied along with the
227  assigned ticket. Subscribes the "all input ports" tracker to this one. */
228  // SystemBase is granted permission to invoke this protected method for use
229  // during Context construction.
230  void AddInputPort(InputPortIndex expected_index, DependencyTicket ticket);
231 
232  /** Adds the next output port. Expected index is supplied along with the
233  assigned ticket. */
234  // SystemBase is granted permission to invoke this protected method for use
235  // during Context construction.
236  void AddOutputPort(
237  OutputPortIndex expected_index, DependencyTicket ticket,
238  const internal::OutputPortPrerequisite& prerequisite);
239 
240  /** Clones a context but without copying any of its internal pointers; the
241  clone's pointers are set to null. */
242  // Structuring this as a static method allows DiagramContext to invoke this
243  // protected function on its children.
244  static std::unique_ptr<ContextBase> CloneWithoutPointers(
245  const ContextBase& source) {
246  return source.DoCloneWithoutPointers();
247  }
248 
249  /** (Internal use only) Given a new context `clone` containing an
250  identically-structured dependency graph as the one in `source`, creates a
251  mapping of all tracker memory addresses from `source` to `clone`. This must be
252  done for the whole Context tree because pointers can point outside of their
253  containing subcontext. */
254  // Structuring this as a static method allows DiagramContext to invoke this
255  // protected function on its children.
256  static void BuildTrackerPointerMap(
257  const ContextBase& source, const ContextBase& clone,
258  DependencyTracker::PointerMap* tracker_map);
259 
260  /** (Internal use only) Assuming `clone` is a recently-cloned Context that
261  has yet to have its internal pointers updated, sets those pointers now. The
262  given map is used to update tracker pointers. */
263  // Structuring this as a static method allows DiagramContext to invoke this
264  // protected function on its children.
265  static void FixContextPointers(
266  const ContextBase& source,
267  const DependencyTracker::PointerMap& tracker_map,
268  ContextBase* clone);
269 
270  /** (Internal use only) Applies the given caching-change notification method
271  to `context`, and propagates the notification to subcontexts if `context` is
272  a DiagramContext. Used, for example, to enable and disable the cache. The
273  supplied `context` is const so depends on the cache being mutable. */
274  // Structuring this as a static method allows DiagramContext to invoke this
275  // protected method on its children.
276  static void PropagateCachingChange(const ContextBase& context,
277  void (Cache::*caching_change)()) {
278  (context.get_mutable_cache().*caching_change)();
279  context.DoPropagateCachingChange(caching_change);
280  }
281 
282  /** Declares that `parent` is the context of the enclosing Diagram.
283  Aborts if the parent has already been set to something else. */
284  // Use static method so DiagramContext can invoke this on behalf of a child.
285  // Output argument is listed first because it is serving as the 'this'
286  // pointer here.
287  static void set_parent(ContextBase* child, const ContextBase* parent) {
288  DRAKE_DEMAND(child != nullptr);
289  child->set_parent(parent);
290  }
291 
292  /** Derived classes must implement this so that it performs the complete
293  deep copy of the context, including all base class members but not fixing
294  up base class pointers. To do that, implement a protected copy constructor
295  that inherits from the base class copy constructor (which doesn't repair the
296  pointers), then implement DoCloneWithoutPointers() as
297  `return unique_ptr<ContextBase>(new DerivedType(*this));`. */
298  virtual std::unique_ptr<ContextBase> DoCloneWithoutPointers() const = 0;
299 
300  /** DiagramContext must implement this to invoke BuildTrackerPointerMap() on
301  each of its subcontexts. The default implementation does nothing which is
302  fine for a LeafContext. */
304  const ContextBase& clone,
305  DependencyTracker::PointerMap* tracker_map) const {
306  unused(clone, tracker_map);
307  }
308 
309  /** DiagramContext must implement this to invoke FixContextPointers() on
310  each of its subcontexts. The default implementation does nothing which is
311  fine for a LeafContext. */
313  const ContextBase& source,
314  const DependencyTracker::PointerMap& tracker_map) {
315  unused(source, tracker_map);
316  }
317 
318  /** DiagramContext must implement this to invoke a caching behavior change on
319  each of its subcontexts. The default implementation does nothing which is
320  fine for a LeafContext. */
321  virtual void DoPropagateCachingChange(void (Cache::*caching_change)()) const {
322  unused(caching_change);
323  }
324 
325  private:
326  friend class detail::SystemBaseContextBaseAttorney;
327 
328  void set_parent(const ContextBase* parent) {
329  DRAKE_DEMAND(parent_ == nullptr || parent_ == parent);
330  parent_ = parent;
331  }
332 
333  // Returns the parent Context or `nullptr` if this is the root Context.
334  const ContextBase* get_parent_base() const { return parent_; }
335 
336  // Records the name of the system whose context this is.
337  void set_system_name(const std::string& name) { system_name_ = name; }
338 
339  // Fixes the input port at `index` to the internal value source `port_value`.
340  // If the port wasn't previously fixed, assigns a ticket and tracker for the
341  // `port_value`, then subscribes the input port to the source's tracker.
342  // If the port was already fixed, we just use the existing tracker and
343  // subscription but replace the value. Notifies the port's downstream
344  // subscribers that the value has changed. Aborts if `index` is out of range,
345  // or the given `port_value` is null or already belongs to a context.
346  void SetFixedInputPortValue(
347  InputPortIndex index,
348  std::unique_ptr<FixedInputPortValue> port_value);
349 
350  // Fills in the dependency graph with the built-in trackers that are common
351  // to every Context (and every System).
352  void CreateBuiltInTrackers();
353 
354  // We record tickets so we can reconstruct the dependency graph when cloning
355  // or transmogrifying a Context without a System present.
356 
357  // Index by InputPortIndex.
358  std::vector<DependencyTicket> input_port_tickets_;
359  // Index by OutputPortIndex.
360  std::vector<DependencyTicket> output_port_tickets_;
361  // Index by DiscreteStateIndex.
362  std::vector<DependencyTicket> discrete_state_tickets_;
363  // Index by AbstractStateIndex.
364  std::vector<DependencyTicket> abstract_state_tickets_;
365  // Index by NumericParameterIndex.
366  std::vector<DependencyTicket> numeric_parameter_tickets_;
367  // Index by AbstractParameterIndex.
368  std::vector<DependencyTicket> abstract_parameter_tickets_;
369 
370  // For each input port, the fixed value or null if the port is connected to
371  // something else (in which case we need System help to get the value).
372  // Semantically, these are identical to Parameters.
373  // Each non-null FixedInputPortValue has a ticket and associated
374  // tracker.
375  // Index with InputPortIndex.
376  std::vector<copyable_unique_ptr<FixedInputPortValue>>
377  input_port_values_;
378 
379  // The cache of pre-computed values owned by this subcontext.
380  mutable Cache cache_;
381 
382  // This is the dependency graph for values within this subcontext.
383  DependencyGraph graph_;
384 
385  // The Context of the enclosing Diagram. Null/invalid when this is the root
386  // context.
388 
389  // Name of the subsystem whose subcontext this is.
390  std::string system_name_;
391 
392  // Used to validate that System-derived classes didn't forget to invoke the
393  // SystemBase method that properly sets up the ContextBase.
394  bool is_context_base_initialized_{false};
395 };
396 
397 #ifndef DRAKE_DOXYGEN_CXX
398 class SystemBase;
399 namespace detail {
400 
401 // This is an attorney-client pattern class providing SystemBase with access to
402 // certain specific ContextBase private methods, and nothing else.
403 class SystemBaseContextBaseAttorney {
404  public:
405  DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SystemBaseContextBaseAttorney)
406  SystemBaseContextBaseAttorney() = delete;
407 
408  private:
409  friend class drake::systems::SystemBase;
410 
411  static void set_system_name(ContextBase* context, const std::string& name) {
412  DRAKE_DEMAND(context != nullptr);
413  context->set_system_name(name);
414  }
415  static const ContextBase* get_parent_base(const ContextBase& context) {
416  return context.get_parent_base();
417  }
418 
419  static void AddInputPort(ContextBase* context, InputPortIndex expected_index,
420  DependencyTicket ticket) {
421  DRAKE_DEMAND(context != nullptr);
422  context->AddInputPort(expected_index, ticket);
423  }
424 
425  static void AddOutputPort(
426  ContextBase* context, OutputPortIndex expected_index,
427  DependencyTicket ticket,
428  const internal::OutputPortPrerequisite& prerequisite) {
429  DRAKE_DEMAND(context != nullptr);
430  context->AddOutputPort(expected_index, ticket, prerequisite);
431  }
432 
433  // Provide SystemBase mutable access to the ticket lists.
434  static std::vector<DependencyTicket>& discrete_state_tickets(
435  ContextBase* context) {
436  DRAKE_DEMAND(context != nullptr);
437  return context->discrete_state_tickets_;
438  }
439  static std::vector<DependencyTicket>& abstract_state_tickets(
440  ContextBase* context) {
441  DRAKE_DEMAND(context != nullptr);
442  return context->abstract_state_tickets_;
443  }
444  static std::vector<DependencyTicket>& numeric_parameter_tickets(
445  ContextBase* context) {
446  DRAKE_DEMAND(context != nullptr);
447  return context->numeric_parameter_tickets_;
448  }
449  static std::vector<DependencyTicket>& abstract_parameter_tickets(
450  ContextBase* context) {
451  DRAKE_DEMAND(context != nullptr);
452  return context->abstract_parameter_tickets_;
453  }
454 
455  static bool is_context_base_initialized(const ContextBase& context) {
456  return context.is_context_base_initialized_;
457  }
458 
459  // SystemBase should invoke this when ContextBase has been successfully
460  // initialized.
461  static void mark_context_base_initialized(ContextBase* context) {
462  DRAKE_DEMAND(context);
463  DRAKE_DEMAND(!context->is_context_base_initialized_);
464  context->is_context_base_initialized_ = true;
465  }
466 };
467 
468 } // namespace detail
469 #endif
470 
471 } // namespace systems
472 } // namespace drake
Manages value interdependencies for a particular value or set of values in a Context.
Definition: dependency_tracker.h:134
virtual std::unique_ptr< ContextBase > DoCloneWithoutPointers() const =0
Derived classes must implement this so that it performs the complete deep copy of the context...
Type wrapper that performs value-initialization on copy construction or assignment.
Definition: reset_on_copy.h:81
double value
Definition: wrap_test_util_py.cc:12
void DisableCaching() const
(Debugging) Disables caching recursively for this context and all its subcontexts.
Definition: context_base.h:63
Definition: automotive_demo.cc:90
const DependencyTracker & get_tracker(DependencyTicket ticket) const
Returns a const reference to a DependencyTracker in this subcontext.
Definition: context_base.h:126
void EnableCaching() const
(Debugging) Re-enables caching recursively for this context and all its subcontexts.
Definition: context_base.h:76
int get_num_output_ports() const
Returns the number of output ports represented in this context.
Definition: context_base.h:155
ContextBase()
Default constructor creates an empty ContextBase but initializes all the built-in dependency trackers...
Definition: context_base.h:215
const FixedInputPortValue * MaybeGetFixedInputPortValue(int index) const
For input port index, returns a const FixedInputPortValue if the port is fixed, otherwise nullptr...
Definition: context_base.h:196
STL namespace.
void AddOutputPort(OutputPortIndex expected_index, DependencyTicket ticket, const internal::OutputPortPrerequisite &prerequisite)
Adds the next output port.
Definition: context_base.cc:63
Represents the portion of the complete dependency graph that is a subgraph centered on the owning sub...
Definition: dependency_tracker.h:442
static std::unique_ptr< ContextBase > CloneWithoutPointers(const ContextBase &source)
Clones a context but without copying any of its internal pointers; the clone&#39;s pointers are set to nu...
Definition: context_base.h:244
DependencyTracker & get_mutable_tracker(DependencyTicket ticket)
Returns a mutable reference to a DependencyTracker in this subcontext.
Definition: context_base.h:132
const DependencyGraph & get_dependency_graph() const
Returns a const reference to the collection of value trackers within this subcontext.
Definition: context_base.h:139
void AddInputPort(InputPortIndex expected_index, DependencyTicket ticket)
Adds the next input port.
Definition: context_base.cc:49
Stores all the CacheEntryValue objects owned by a particular Context, organized to allow fast access ...
Definition: cache.h:592
Provides non-templatized functionality shared by the templatized derived classes. ...
Definition: context_base.h:38
std::unique_ptr< KinematicsCache< double > > cache_
Definition: differential_inverse_kinematics_test.cc:106
#define DRAKE_ASSERT(condition)
DRAKE_ASSERT(condition) is similar to the built-in assert(condition) from the C++ system header <cas...
Definition: drake_assert.h:37
static void set_parent(ContextBase *child, const ContextBase *parent)
Declares that parent is the context of the enclosing Diagram.
Definition: context_base.h:287
Cache & get_mutable_cache() const
(Advanced) Returns a mutable reference to this subcontext&#39;s cache.
Definition: context_base.h:119
Declares CacheEntryValue and Cache, which is the container for cache entry values.
#define DRAKE_DEMAND(condition)
Evaluates condition and iff the value is false will trigger an assertion failure with a message showi...
Definition: drake_assert.h:45
virtual void DoPropagateFixContextPointers(const ContextBase &source, const DependencyTracker::PointerMap &tracker_map)
DiagramContext must implement this to invoke FixContextPointers() on each of its subcontexts.
Definition: context_base.h:312
void SetAllCacheEntriesOutOfDate() const
(Debugging) Marks all cache entries out of date, recursively for this context and all its subcontexts...
Definition: context_base.h:88
DependencyGraph & get_mutable_dependency_graph()
Returns a mutable reference to the dependency graph.
Definition: context_base.h:144
DependencyTicket input_port_ticket(InputPortIndex port_num)
Returns the dependency ticket associated with a particular input port.
Definition: context_base.h:160
Provides non-templatized functionality shared by the templatized System classes.
Definition: system_base.h:29
std::unordered_map< const DependencyTracker *, const DependencyTracker * > PointerMap
(Internal use only)
Definition: dependency_tracker.h:140
virtual void DoPropagateCachingChange(void(Cache::*caching_change)()) const
DiagramContext must implement this to invoke a caching behavior change on each of its subcontexts...
Definition: context_base.h:321
A fully type-erased container class.
Definition: value.h:101
int get_num_input_ports() const
Returns the number of input ports in this context.
Definition: context_base.h:149
FixedInputPortValue & FixInputPort(int index, const AbstractValue &value)
Same as above method but the value is passed by const reference instead of by unique_ptr.
Definition: context_base.h:189
FixedInputPortValue * MaybeGetMutableFixedInputPortValue(int index)
For input port index, returns a mutable FixedInputPortValue if the port is fixed, otherwise nullptr...
Definition: context_base.h:204
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.
Definition: context_base.h:276
Declares DependencyTracker and DependencyGraph which is the container for trackers.
void DisableCaching()
(Advanced) Disables caching for all the entries in this Cache.
Definition: cache.cc:112
void EnableCaching()
(Advanced) Re-enables caching for all entries in this Cache if any were previously disabled...
Definition: cache.cc:118
virtual std::unique_ptr< AbstractValue > Clone() const =0
Returns a copy of this AbstractValue.
A FixedInputPortValue encapsulates a vector or abstract value for use as an internal value source for...
Definition: fixed_input_port_value.h:35
#define DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN deletes the special member functions for copy-construction, copy-assignment, move-construction, and move-assignment.
Definition: drake_copyable.h:33
virtual void DoPropagateBuildTrackerPointerMap(const ContextBase &clone, DependencyTracker::PointerMap *tracker_map) const
DiagramContext must implement this to invoke BuildTrackerPointerMap() on each of its subcontexts...
Definition: context_base.h:303
DependencyTicket output_port_ticket(OutputPortIndex port_num)
Returns the dependency ticket associated with a particular output port.
Definition: context_base.h:166
void SetAllEntriesOutOfDate()
(Advanced) Mark every entry in this cache as "out of date".
Definition: cache.cc:123
const Cache & get_cache() const
Returns a const reference to this subcontext&#39;s cache.
Definition: context_base.h:107
const std::string & GetSystemName() const final
Returns the local name of the subsystem for which this is the Context.
Definition: context_base.h:96
void unused(const Args &...)
Documents the argument(s) as unused, placating GCC&#39;s -Wunused-parameter warning.
Definition: unused.h:51