Drake
system_base.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <memory>
4 #include <set>
5 #include <string>
6 #include <utility>
7 #include <vector>
8 
10 #include "drake/common/unused.h"
15 
16 namespace drake {
17 namespace systems {
18 
19 /** Provides non-templatized functionality shared by the templatized System
20 classes.
21 
22 Terminology: in general a Drake System is a tree structure composed of
23 "subsystems", which are themselves System objects. The corresponding Context is
24 a parallel tree structure composed of "subcontexts", which are themselves
25 Context objects. There is a one-to-one correspondence between subsystems and
26 subcontexts. Within a given System (Context), its child subsystems (subcontexts)
27 are indexed using a SubsystemIndex; there is no separate SubcontextIndex since
28 the numbering must be identical. */
29 class SystemBase : public internal::SystemMessageInterface {
30  public:
32 
33  ~SystemBase() override;
34 
35  /** Sets the name of the system. Do not use the path delimiter character ':'
36  in the name. When creating a Diagram, names of sibling subsystems should be
37  unique. DiagramBuilder uses this method to assign a unique default name if
38  none is provided. */
39  // TODO(sherm1) Enforce reasonable naming policies.
40  void set_name(const std::string& name) { name_ = name; }
41 
42  /** Returns the name last supplied to set_name(), if any. Diagrams built with
43  DiagramBuilder will always have a default name for every contained subsystem
44  for which no user-provided name is available. Systems created by copying with
45  a scalar type change have the same name as the source system. An empty string
46  is returned if no name has been set. */
47  // TODO(sherm1) This needs to be better distinguished from the human-readable
48  // name. Consider an api change like get_label() for this one, with the
49  // intent that the label could be used programmatically.
50  const std::string& get_name() const { return name_; }
51 
52  /** Returns a human-readable name for this system, for use in messages and
53  logging. This will be the same as returned by get_name(), unless that would
54  be an empty string. In that case we return a non-unique placeholder name,
55  currently just "_" (a lone underscore). */
56  const std::string& GetSystemName() const final {
57  return name_.empty() ? internal::SystemMessageInterface::no_name() : name_;
58  }
59 
60  /** Generates and returns a human-readable full path name of this subsystem,
61  for use in messages and logging. The name starts from the root System, with
62  "::" delimiters between parent and child subsystems, with the individual
63  subsystems represented by their names as returned by GetSystemName(). */
64  std::string GetSystemPathname() const final;
65 
66  /** Returns the most-derived type of this concrete System object as a
67  human-readable string suitable for use in error messages. The format is as
68  generated by NiceTypeName and will include namespace qualification if
69  present.
70  @see NiceTypeName for more specifics. */
71  std::string GetSystemType() const final { return NiceTypeName::Get(*this); }
72 
73  /** Throws an exception with an appropriate message if the given `context` is
74  not compatible with this System. Restrictions may vary for different systems;
75  the error message should explain. This can be an expensive check so you may
76  want to limit it to Debug builds. */
77  void ThrowIfContextNotCompatible(const ContextBase& context) const final {
78  CheckValidContext(context);
79  }
80 
81  /** Returns a Context suitable for use with this System. Context resources
82  are allocated based on resource requests that were made during System
83  construction. */
84  std::unique_ptr<ContextBase> AllocateContext() const {
85  // Get a concrete Context of the right type, allocate internal resources
86  // like parameters, state, and cache entries, and set up intra- and
87  // inter-subcontext dependencies.
88  std::unique_ptr<ContextBase> context = DoAllocateContext();
89 
90  // We depend on derived classes to call our InitializeContextBase() method
91  // after allocating the appropriate concrete Context.
93  detail::SystemBaseContextBaseAttorney::is_context_base_initialized(
94  *context));
95 
96  return context;
97  }
98 
99  //----------------------------------------------------------------------------
100  /** @name Input port evaluation
101  These methods provide scalar type-independent evaluation of a System input
102  port in a particular Context. If necessary, they first cause the port's value
103  to become up to date, then they return a reference to the now-up-to-date value
104  in the given Context.
105 
106  Specified preconditions for these methods operate as follows: The
107  preconditions will be checked in Debug builds but some or all might not be
108  checked in Release builds for performance reasons. If we do check, and a
109  precondition is violated, an std::logic_error will be thrown with a helpful
110  message.
111 
112  @see System::EvalVectorInput(), System::EvalEigenVectorInput() for
113  scalar type-specific input port access. */
114  //@{
115 
116  /** Returns the value of the input port with the given `port_index` as an
117  AbstractValue, which is permitted for ports of any type. Causes the value to
118  become up to date first if necessary, delegating to our parent Diagram.
119  Returns a pointer to the port's value, or nullptr if the port is not
120  connected. If you know the actual type, use one of the more-specific
121  signatures.
122 
123  @pre `port_index` selects an existing input port of this System.
124 
125  @see EvalInputValue(), System::EvalVectorInput(),
126  System::EvalEigenVectorInput() */
128  int port_index) const {
129  if (port_index < 0)
130  ThrowNegativePortIndex(__func__, port_index);
131  const InputPortIndex port(port_index);
132  return EvalAbstractInputImpl(__func__, context, port);
133  }
134 
135  /** Returns the value of an abstract-valued input port with the given
136  `port_index` as a value of known type `V`. Causes the value to become
137  up to date first if necessary. See EvalAbstractInput() for
138  more information.
139 
140  The result is returned as a pointer to the input port's value of type `V`,
141  or nullptr if the port is not connected.
142 
143  @pre `port_index` selects an existing input port of this System.
144  @pre the port's value must be retrievable from the stored abstract value
145  using `AbstractValue::GetValue<V>`.
146 
147  @tparam V The type of data expected. */
148  template <typename V>
149  const V* EvalInputValue(const ContextBase& context, int port_index) const {
150  if (port_index < 0)
151  ThrowNegativePortIndex(__func__, port_index);
152  const InputPortIndex port(port_index);
153 
154  const AbstractValue* const abstract_value =
155  EvalAbstractInputImpl(__func__, context, port);
156  if (abstract_value == nullptr)
157  return nullptr; // An unconnected port.
158 
159  // We have a value, is it a V?
160  const V* const value = abstract_value->MaybeGetValue<V>();
161  if (value == nullptr) {
162  ThrowInputPortHasWrongType(__func__, port, NiceTypeName::Get<V>(),
163  abstract_value->GetNiceTypeName());
164  }
165 
166  return value;
167  }
168  //@}
169 
170  /** Returns the number of input ports currently allocated in this System.
171  These are indexed from 0 to %get_num_input_ports()-1. */
172  int get_num_input_ports() const {
173  return static_cast<int>(input_ports_.size());
174  }
175 
176  /** Returns the number of output ports currently allocated in this System.
177  These are indexed from 0 to %get_num_output_ports()-1. */
178  int get_num_output_ports() const {
179  return static_cast<int>(output_ports_.size());
180  }
181 
182  /** Returns a reference to an InputPort given its `port_index`.
183  @pre `port_index` selects an existing input port of this System. */
185  return GetInputPortBaseOrThrow(__func__, port_index);
186  }
187 
188  /** Returns a reference to an OutputPort given its `port_index`.
189  @pre `port_index` selects an existing output port of this System. */
191  return GetOutputPortBaseOrThrow(__func__, port_index);
192  }
193 
194  /** Returns the total dimension of all of the vector-valued input ports (as if
195  they were muxed). */
196  int get_num_total_inputs() const {
197  int count = 0;
198  for (const auto& in : input_ports_) count += in->size();
199  return count;
200  }
201 
202  /** Returns the total dimension of all of the vector-valued output ports (as
203  if they were muxed). */
204  int get_num_total_outputs() const {
205  int count = 0;
206  for (const auto& out : output_ports_) count += out->size();
207  return count;
208  }
209 
210  /** Returns the number nc of cache entries currently allocated in this System.
211  These are indexed from 0 to nc-1. */
212  int num_cache_entries() const {
213  return static_cast<int>(cache_entries_.size());
214  }
215 
216  /** Return a reference to a CacheEntry given its `index`. */
217  const CacheEntry& get_cache_entry(CacheIndex index) const {
218  DRAKE_ASSERT(0 <= index && index < num_cache_entries());
219  return *cache_entries_[index];
220  }
221 
222  // TODO(sherm1) Consider whether to make DeclareCacheEntry methods protected.
223  //============================================================================
224  /** @name Declare cache entries
225  @anchor DeclareCacheEntry_documentation
226 
227  Methods in this section are used by derived classes to declare cache entries
228  for their own internal computations. (Other cache entries are provided
229  automatically for well-known computations such as output ports and time
230  derivatives.) Cache entries may contain values of any type, however the type
231  for any particular cache entry is fixed after first allocation. Every cache
232  entry must have an _allocator_ function `Alloc()` and a _calculator_ function
233  `Calc()`. `Alloc()` returns an object suitable for holding a value of the
234  cache entry. `Calc()` uses the contents of a given Context to produce the
235  cache entry's value, which is placed in an object of the type returned by
236  `Alloc()`.
237 
238  <h4>Prerequisites</h4>
239 
240  Correct runtime caching behavior depends critically on understanding the
241  dependencies of the cache entry's `Calc()` function (we call those
242  "prerequisites"). If none of the prerequisites has changed since the last
243  time `Calc()` was invoked to set the cache entry's value, then we don't need
244  to perform a potentially expensive recalculation. On the other hand, if any
245  of the prerequisites has changed then the current value is invalid and must
246  not be used without first recomputing.
247 
248  Currently it is not possible for Drake to infer prerequisites accurately and
249  automatically from inspection of the `Calc()` implementation. Therefore,
250  if you don't say otherwise, Drake will assume `Calc()` is dependent
251  on all value sources in the Context, including time, state, input ports,
252  parameters, and accuracy. That means the cache entry's value will be
253  considered invalid if _any_ of those sources has changed since the last time
254  the value was calculated. That is safe, but can result in more computation
255  than necessary. If you know that your `Calc()` method has fewer prerequisites,
256  you may say so by providing an explicit list in the `prerequisites_of_calc`
257  parameter. Every possible prerequisite has a DependencyTicket ("ticket"), and
258  the list should consist of tickets. For example, if your calculator depends
259  only on time (e.g. `Calc(context)` is `sin(context.get_time())`) then you
260  would specify `prerequisites_of_calc={time_ticket()}` here. See
261  @ref DependencyTicket_documentation "Dependency tickets" for a list of the
262  possible tickets and what they mean.
263 
264  @warning It is critical that the prerequisite list you supply be accurate, or
265  at least conservative, for correct functioning of the caching system. Drake
266  cannot currently detect that a `Calc()` function accesses an undeclared
267  prerequisite. Even assuming you have correctly listed the prerequisites, you
268  should include a prominent comment in every `Calc()` implementation noting
269  that if the implementation is changed then the prerequisite list must be
270  updated correspondingly.
271 
272  A technique you can use to ensure that prerequisites have been properly
273  specified is to make use of the Context's
274  @ref drake::systems::ContextBase::DisableCaching "DisableCaching()"
275  method, which causes cache values to be recalculated unconditionally. You
276  should get identical results with caching enabled or disabled, with speed
277  being the only difference.
278  @see drake::systems::ContextBase::DisableCaching()
279 
280  <h4>Which signature to use?</h4>
281 
282  Although the allocator and calculator functions ultimately satisfy generic
283  function signatures defined in CacheEntry, we provide a variety
284  of `DeclareCacheEntry()` signatures here for convenient specification,
285  with mapping to the generic form handled invisibly. In particular,
286  allocators are most easily defined by providing a model value that can be
287  used to construct an allocator that copies the model when a new value
288  object is needed. Alternatively a method can be provided that constructs
289  a value object when invoked (those methods are conventionally, but not
290  necessarily, named `MakeSomething()` where `Something` is replaced by the
291  cache entry value type).
292 
293  Because cache entry values are ultimately stored in AbstractValue objects,
294  the underlying types must be suitable. That means the type must be copy
295  constructible or cloneable. For methods below that are not given an explicit
296  model value or construction ("make") method, the underlying type must also be
297  default constructible.
298  @see drake::systems::Value for more about abstract values. */
299  //@{
300 
301  /// @anchor DeclareCacheEntry_primary
302  /** Declares a new %CacheEntry in this System using the least-restrictive
303  definitions for the associated functions. Prefer one of the more-convenient
304  signatures below if you can. The new cache entry is assigned a unique
305  CacheIndex and DependencyTicket, which can be obtained from the returned
306  %CacheEntry. The function signatures here are:
307  @code
308  std::unique_ptr<AbstractValue> Alloc();
309  void Calc(const ContextBase&, AbstractValue*);
310  @endcode
311  where the AbstractValue objects must resolve to the same concrete type.
312 
313  @param[in] description
314  A human-readable description of this cache entry, most useful for debugging
315  and documentation. Not interpreted in any way by Drake; it is retained
316  by the cache entry and used to generate the description for the
317  corresponding CacheEntryValue in the Context.
318  @param[in] alloc_function
319  Given a Context, returns a heap-allocated AbstractValue object suitable for
320  holding a value for this cache entry.
321  @param[in] calc_function
322  Provides the computation that maps from a given Context to the current
323  value that this cache entry should have, and writes that value to a given
324  object of the type returned by `alloc_function`.
325  @param[in] prerequisites_of_calc
326  Provides the DependencyTicket list containing a ticket for _every_ Context
327  value on which `calc_function` may depend when it computes its result.
328  Defaults to `{all_sources_ticket()}` if unspecified. If the cache value
329  is truly independent of the Context (rare!) say so explicitly by providing
330  the list `{nothing_ticket()}`; an explicitly empty list `{}` is forbidden.
331  @returns a const reference to the newly-created %CacheEntry.
332  @throws std::logic_error if given an explicitly empty prerequisite list. */
333  // Arguments to these methods are moved from internally. Taking them by value
334  // rather than reference avoids a copy when the original argument is
335  // an rvalue.
337  std::string description, CacheEntry::AllocCallback alloc_function,
338  CacheEntry::CalcCallback calc_function,
339  std::set<DependencyTicket> prerequisites_of_calc = {
340  all_sources_ticket()});
341 
342  /** Declares a cache entry by specifying member functions to use both for the
343  allocator and calculator. The signatures are: @code
344  ValueType MySystem::MakeValueType() const;
345  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
346  @endcode
347  where `MySystem` is a class derived from `SystemBase`, `MyContext` is a class
348  derived from `ContextBase`, and `ValueType` is any concrete type such that
349  `Value<ValueType>` is permitted. (The method names are arbitrary.) Template
350  arguments will be deduced and do not need to be specified. See the
351  @ref DeclareCacheEntry_primary "primary DeclareCacheEntry() signature"
352  for more information about the parameters and behavior.
353  @see drake::systems::Value */
354  template <class MySystem, class MyContext, typename ValueType>
356  std::string description,
357  ValueType (MySystem::*make)() const,
358  void (MySystem::*calc)(const MyContext&, ValueType*) const,
359  std::set<DependencyTicket> prerequisites_of_calc = {
360  all_sources_ticket()});
361 
362  /// @anchor DeclareCacheEntry_model_and_calc
363  /** Declares a cache entry by specifying a model value of concrete type
364  `ValueType` and a calculator function that is a class member function (method)
365  with signature: @code
366  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
367  @endcode
368  where `MySystem` is a class derived from `SystemBase`, `MyContext` is a class
369  derived from `ContextBase`, and `ValueType` is any concrete type such that
370  `Value<ValueType>` is permitted. (The method names are arbitrary.) Template
371  arguments will be deduced and do not need to be specified. See the
372  @ref DeclareCacheEntry_primary "primary DeclareCacheEntry() signature"
373  above for more information about the parameters and behavior.
374  @see drake::systems::Value */
375  template <class MySystem, class MyContext, typename ValueType>
377  std::string description, const ValueType& model_value,
378  void (MySystem::*calc)(const MyContext&, ValueType*) const,
379  std::set<DependencyTicket> prerequisites_of_calc = {
380  all_sources_ticket()});
381 
382  /** Declares a cache entry by specifying a model value of concrete type
383  `ValueType` and a calculator function that is a class member function (method)
384  with signature: @code
385  ValueType MySystem::CalcCacheValue(const MyContext&) const;
386  @endcode
387  Other than the calculator signature, this is identical to the other
388  @ref DeclareCacheEntry_model_and_calc "model and calculator signature",
389  please look there for more information. */
390  template <class MySystem, class MyContext, typename ValueType>
392  std::string description, const ValueType& model_value,
393  ValueType (MySystem::*calc)(const MyContext&) const,
394  std::set<DependencyTicket> prerequisites_of_calc = {
395  all_sources_ticket()});
396 
397  /// @anchor DeclareCacheEntry_calc_only
398  /** Declares a cache entry by specifying only a calculator function that is a
399  class member function (method) with signature:
400  @code
401  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
402  @endcode
403  where `MySystem` is a class derived from `SystemBase` and `MyContext` is a
404  class derived from `ContextBase`. `ValueType` is a concrete type such that
405  (a) `Value<ValueType>` is permitted, and (b) `ValueType` is default
406  constructible. That allows us to create a model value using
407  `Value<ValueType>{}` (value initialized so numerical types will be zeroed in
408  the model). (The method name is arbitrary.) Template arguments will be
409  deduced and do not need to be specified. See the first DeclareCacheEntry()
410  signature above for more information about the parameters and behavior.
411 
412  @note The default constructor will be called once immediately to create a
413  model value, and subsequent allocations will just copy the model value without
414  invoking the constructor again. If you want the constructor invoked again at
415  each allocation (not common), use one of the other signatures to explicitly
416  provide a method for the allocator to call; that method can then invoke
417  the `ValueType` default constructor each time it is called.
418  @see drake::systems::Value */
419  template <class MySystem, class MyContext, typename ValueType>
421  std::string description,
422  void (MySystem::*calc)(const MyContext&, ValueType*) const,
423  std::set<DependencyTicket> prerequisites_of_calc = {
424  all_sources_ticket()});
425 
426  /** Declares a cache entry by specifying only a calculator function that is a
427  class member function (method) with signature:
428  @code
429  ValueType MySystem::CalcCacheValue(const MyContext&) const;
430  @endcode
431  Other than the calculator method's signature, this is identical to the other
432  @ref DeclareCacheEntry_calc_only "calculator-only signature";
433  please look there for more information. */
434  template <class MySystem, class MyContext, typename ValueType>
436  std::string description,
437  ValueType (MySystem::*calc)(const MyContext&) const,
438  std::set<DependencyTicket> prerequisites_of_calc = {
439  all_sources_ticket()});
440  //@}
441 
442  /** Checks whether the given context is valid for this System and throws
443  an exception with a helpful message if not. This is *very* expensive and
444  should generally be done only in Debug builds, like this:
445  @code
446  DRAKE_ASSERT_VOID(CheckValidContext(context));
447  @endcode */
448  void CheckValidContext(const ContextBase& context) const {
449  // TODO(sherm1) Add base class checks.
450 
451  // Let derived classes have their say.
452  DoCheckValidContext(context);
453  }
454 
455  //============================================================================
456  /** @name Dependency tickets
457  @anchor DependencyTicket_documentation
458 
459  Use these tickets to declare well-known sources as prerequisites of a
460  downstream computation such as an output port, derivative, update, or cache
461  entry. The ticket numbers for the built-in sources are the same for all
462  systems. For time and accuracy they refer to the same global resource;
463  otherwise they refer to the specified sources within the referencing system.
464 
465  A dependency ticket for a more specific resource (a particular input or
466  output port, a discrete variable group, abstract state variable, a parameter,
467  or a cache entry) is allocated and stored with the resource when it is
468  declared. Usually the tickets are obtained directly from the resource but
469  you can recover them with methods here knowing only the resource index. */
470  //@{
471 
472  // The DependencyTrackers associated with these tickets are allocated
473  // in ContextBase::CreateBuiltInTrackers() and the implementation there must
474  // be kept up to date with the API contracts here.
475 
476  // The ticket methods are promoted in the System<T> class so that users can
477  // invoke them in their constructors without prefixing with this->. If you
478  // add, remove, rename, or reorder any of these be sure to update the
479  // promotions in system.h.
480 
481  // Keep the order here the same as they are defined in the internal enum
482  // BuiltInTicketNumbers, with the "particular resource" indexed methods
483  // inserted prior to the corresponding built-in "all such resources" ticket.
484 
485  /** Returns a ticket indicating that a computation does not depend on *any*
486  source value; that is, it is a constant. If this appears in a prerequisite
487  list, it must be the only entry. */
489  return DependencyTicket(internal::kNothingTicket);
490  }
491 
492  /** Returns a ticket indicating dependence on time. This is the same ticket
493  for all systems and refers to the same time value. */
495  return DependencyTicket(internal::kTimeTicket);
496  }
497 
498  /** Returns a ticket indicating dependence on the accuracy setting in the
499  Context. This is the same ticket for all systems and refers to the same
500  accuracy value. */
502  return DependencyTicket(internal::kAccuracyTicket);
503  }
504 
505  /** Returns a ticket indicating that a computation depends on configuration
506  state variables q. There is no ticket representing just one of the state
507  variables qᵢ. */
509  return DependencyTicket(internal::kQTicket);
510  }
511 
512  /** Returns a ticket indicating dependence on velocity state variables v. This
513  does _not_ also indicate a dependence on configuration variables q -- you must
514  list that explicitly or use kinematics_ticket() instead. There is no ticket
515  representing just one of the state variables vᵢ. */
517  return DependencyTicket(internal::kVTicket);
518  }
519 
520  /** Returns a ticket indicating dependence on any or all of the miscellaneous
521  continuous state variables z. There is no ticket representing just one of
522  the state variables zᵢ. */
524  return DependencyTicket(internal::kZTicket);
525  }
526 
527  /** Returns a ticket indicating dependence on _all_ of the continuous
528  state variables q, v, or z. */
530  return DependencyTicket(internal::kXcTicket);
531  }
532 
533  /** Returns a ticket indicating dependence on a particular discrete state
534  variable xdᵢ (may be a vector). (We sometimes refer to this as a "discrete
535  variable group".)
536  @see xd_ticket() to obtain a ticket for _all_ discrete variables. */
538  return discrete_state_tracker_info(index).ticket;
539  }
540 
541  /** Returns a ticket indicating dependence on all of the numerical
542  discrete state variables, in any discrete variable group.
543  @see discrete_state_ticket() to obtain a ticket for just one discrete
544  state variable. */
546  return DependencyTicket(internal::kXdTicket);
547  }
548 
549  /** Returns a ticket indicating dependence on a particular abstract state
550  variable xaᵢ.
551  @see xa_ticket() to obtain a ticket for _all_ abstract variables. */
553  return abstract_state_tracker_info(index).ticket;
554  }
555 
556  /** Returns a ticket indicating dependence on all of the abstract
557  state variables in the current Context.
558  @see abstract_state_ticket() to obtain a ticket for just one abstract
559  state variable. */
561  return DependencyTicket(internal::kXaTicket);
562  }
563 
564  /** Returns a ticket indicating dependence on _all_ state variables x in this
565  system, including continuous variables xc, discrete (numeric) variables xd,
566  and abstract state variables xa. This does not imply dependence on time,
567  accuracy, parameters, or inputs; those must be specified separately. If you
568  mean to express dependence on all possible value sources, use
569  all_sources_ticket() instead. */
571  return DependencyTicket(internal::kXTicket);
572  }
573 
574  /** Returns a ticket indicating dependence on a particular numeric parameter
575  pnᵢ (may be a vector).
576  @see pn_ticket() to obtain a ticket for _all_ numeric parameters. */
578  return numeric_parameter_tracker_info(index).ticket;
579  }
580 
581  /** Returns a ticket indicating dependence on all of the numerical
582  parameters in the current Context.
583  @see numeric_parameter_ticket() to obtain a ticket for just one numeric
584  parameter. */
586  return DependencyTicket(internal::kPnTicket);
587  }
588 
589  /** Returns a ticket indicating dependence on a particular abstract
590  parameter paᵢ.
591  @see pa_ticket() to obtain a ticket for _all_ abstract parameters. */
593  AbstractParameterIndex index) const {
594  return abstract_parameter_tracker_info(index).ticket;
595  }
596 
597  /** Returns a ticket indicating dependence on all of the abstract
598  parameters pa in the current Context.
599  @see abstract_parameter_ticket() to obtain a ticket for just one abstract
600  parameter. */
602  return DependencyTicket(internal::kPaTicket);
603  }
604 
605  /** Returns a ticket indicating dependence on _all_ parameters p in this
606  system, including numeric parameters pn, and abstract parameters pa. */
608  return DependencyTicket(internal::kAllParametersTicket);
609  }
610 
611  /** Returns a ticket indicating dependence on input port uᵢ indicated
612  by `index`.
613  @pre `index` selects an existing input port of this System. */
615  DRAKE_DEMAND(0 <= index && index < get_num_input_ports());
616  return input_ports_[index]->ticket();
617  }
618 
619  /** Returns a ticket indicating dependence on _all_ input ports u of this
620  system.
621  @see input_port_ticket() to obtain a ticket for just one input port. */
623  return DependencyTicket(internal::kAllInputPortsTicket);
624  }
625 
626  /** Returns a ticket indicating dependence on every possible independent
627  source value, including time, accuracy, state, input ports, and parameters
628  (but not cache entries). This is the default dependency for computations that
629  have not specified anything more refined.
630  @see cache_entry_ticket() to obtain a ticket for a cache entry. */
632  return DependencyTicket(internal::kAllSourcesTicket);
633  }
634 
635  /** Returns a ticket indicating dependence on the cache entry indicated
636  by `index`. Note that cache entries are _not_ included in the `all_sources`
637  ticket so must be listed separately.
638  @pre `index` selects an existing cache entry in this System. */
640  DRAKE_DEMAND(0 <= index && index < num_cache_entries());
641  return cache_entries_[index]->ticket();
642  }
643 
644  /** Returns a ticket indicating dependence on all source values that may
645  affect configuration-dependent computations. In particular, this category
646  _does not_ include time, generalized velocities v, or input ports.
647  Generalized coordinates q are included, as well as any discrete state
648  variables that have been declared as configuration variables, and
649  configuration-affecting parameters. Finally we assume that
650  the accuracy setting may affect some configuration-dependent computations.
651  Examples: a parameter that affects length may change the computation of an
652  end-effector location. A change in accuracy requirement may require
653  recomputation of an iterative approximation of contact forces.
654  @see kinematics_ticket()
655 
656  @bug Currently there is no way to declare specific variables and parameters
657  to be configuration-affecting so we include all state variables and
658  parameters except for generalized velocities v. */
659  // TODO(sherm1) Remove the above bug notice once #9171 is resolved.
660  // The configuration_tracker implementation in ContextBase must be kept
661  // up to date with the above API contract.
663  return DependencyTicket(internal::kConfigurationTicket);
664  }
665 
666  /** Returns a ticket indicating dependence on all source values that may
667  affect configuration- or velocity-dependent computations. This ticket depends
668  on the configuration_ticket defined above, and adds in velocity-affecting
669  source values. This _does not_ include time or input ports.
670  @see configuration_ticket()
671 
672  @bug Currently there is no way to declare specific variables and parameters
673  to be configuration- or velocity-affecting so we include all state variables
674  and parameters. */
675  // TODO(sherm1) Remove the above bug notice once #9171 is resolved.
677  return DependencyTicket(internal::kKinematicsTicket);
678  }
679 
680  /** Returns a ticket for the cache entry that holds time derivatives of
681  the continuous variables.
682  @see EvalTimeDerivatives() */
684  return DependencyTicket(internal::kXcdotTicket);
685  }
686 
687  /** Returns a ticket for the cache entry that holds the potential energy
688  calculation.
689  @see System::EvalPotentialEnergy() */
691  return DependencyTicket(internal::kPeTicket);
692  }
693 
694  /** Returns a ticket for the cache entry that holds the kinetic energy
695  calculation.
696  @see System::EvalKineticEnergy() */
698  return DependencyTicket(internal::kKeTicket);
699  }
700 
701  /** Returns a ticket for the cache entry that holds the conservative power
702  calculation.
703  @see System::EvalConservativePower() */
705  return DependencyTicket(internal::kPcTicket);
706  }
707 
708  /** Returns a ticket for the cache entry that holds the non-conservative
709  power calculation.
710  @see System::EvalNonConservativePower() */
712  return DependencyTicket(internal::kPncTicket);
713  }
714 
715  /** (Internal use only) Returns a ticket indicating dependence on the output
716  port indicated by `index`. No user-definable quantities in a system can
717  meaningfully depend on that system's own output ports.
718  @pre `index` selects an existing output port of this System. */
720  DRAKE_DEMAND(0 <= index && index < get_num_output_ports());
721  return output_ports_[index]->ticket();
722  }
723 
724  /** Returns the number of declared discrete state groups (each group is
725  a vector-valued discrete state variable). */
727  return static_cast<int>(discrete_state_tickets_.size());
728  }
729 
730  /** Returns the number of declared abstract state variables. */
731  int num_abstract_states() const {
732  return static_cast<int>(abstract_state_tickets_.size());
733  }
734 
735  /** Returns the number of declared numeric parameters (each of these is
736  a vector-valued parameter). */
738  return static_cast<int>(numeric_parameter_tickets_.size());
739  }
740 
741  /** Returns the number of declared abstract parameters. */
743  return static_cast<int>(abstract_parameter_tickets_.size());
744  }
745  //@}
746 
747  protected:
748  /** (Internal use only) Default constructor. */
749  SystemBase() = default;
750 
751  /** (Internal use only) Adds an already-constructed input port to this System.
752  Insists that the port already contains a reference to this System, and that
753  the port's index is already set to the next available input port index for
754  this System. */
755  // TODO(sherm1) Add check on suitability of `size` parameter for the port's
756  // data type.
757  void AddInputPort(std::unique_ptr<InputPortBase> port) {
758  DRAKE_DEMAND(port != nullptr);
759  DRAKE_DEMAND(&port->get_system_base() == this);
760  DRAKE_DEMAND(port->get_index() == this->get_num_input_ports());
761  input_ports_.push_back(std::move(port));
762  }
763 
764  /** (Internal use only) Adds an already-constructed output port to this
765  System. Insists that the port already contains a reference to this System, and
766  that the port's index is already set to the next available output port index
767  for this System. */
768  // TODO(sherm1) Add check on suitability of `size` parameter for the port's
769  // data type.
770  void AddOutputPort(std::unique_ptr<OutputPortBase> port) {
771  DRAKE_DEMAND(port != nullptr);
772  DRAKE_DEMAND(&port->get_system_base() == this);
773  DRAKE_DEMAND(port->get_index() == this->get_num_output_ports());
774  output_ports_.push_back(std::move(port));
775  }
776 
777  /** (Internal use only) Assigns a ticket to a new discrete variable group
778  with the given `index`.
779  @pre The supplied index must be the next available one; that is, indexes
780  must be assigned sequentially. */
784  discrete_state_tickets_.push_back(
785  {ticket, "discrete state group " + std::to_string(index)});
786  }
787 
788  /** (Internal use only) Assigns a ticket to a new abstract state variable with
789  the given `index`.
790  @pre The supplied index must be the next available one; that is, indexes
791  must be assigned sequentially. */
794  DRAKE_DEMAND(index == num_abstract_states());
795  abstract_state_tickets_.push_back(
796  {ticket, "abstract state " + std::to_string(index)});
797  }
798 
799  /** (Internal use only) Assigns a ticket to a new numeric parameter with
800  the given `index`.
801  @pre The supplied index must be the next available one; that is, indexes
802  must be assigned sequentially. */
806  numeric_parameter_tickets_.push_back(
807  {ticket, "numeric parameter " + std::to_string(index)});
808  }
809 
810  /** (Internal use only) Assigns a ticket to a new abstract parameter with
811  the given `index`.
812  @pre The supplied index must be the next available one; that is, indexes
813  must be assigned sequentially. */
817  abstract_parameter_tickets_.push_back(
818  {ticket, "abstract parameter " + std::to_string(index)});
819  }
820 
821  /** (Internal use only) This is for cache entries associated with pre-defined
822  tickets, for example the cache entry for time derivatives. See the public API
823  for the most-general DeclareCacheEntry() signature for the meanings of the
824  other parameters here. */
826  DependencyTicket known_ticket,
827  std::string description, CacheEntry::AllocCallback alloc_function,
828  CacheEntry::CalcCallback calc_function,
829  std::set<DependencyTicket> prerequisites_of_calc = {
830  all_sources_ticket()});
831 
832  /** Returns a pointer to the service interface of the immediately enclosing
833  Diagram if one has been set, otherwise nullptr. */
834  const internal::SystemParentServiceInterface* get_parent_service() const {
835  return parent_service_;
836  }
837 
838  /** (Internal use only) Assigns the next unused dependency ticket number,
839  unique only within a particular system. Each call to this method increments
840  the ticket number. */
842  return next_available_ticket_++;
843  }
844 
845  /** (Internal use only) Declares that `parent_service` is the service
846  interface of the Diagram that owns this subsystem. Aborts if the parent
847  service has already been set to something else. */
848  // Use static method so Diagram can invoke this on behalf of a child.
849  // Output argument is listed first because it is serving as the 'this'
850  // pointer here.
851  static void set_parent_service(
852  SystemBase* child,
853  const internal::SystemParentServiceInterface* parent_service) {
854  DRAKE_DEMAND(child != nullptr && parent_service != nullptr);
855  DRAKE_DEMAND(child->parent_service_ == nullptr ||
856  child->parent_service_ == parent_service);
857  child->parent_service_ = parent_service;
858  }
859 
860  /** (Internal use only) Shared code for updating an input port and returning a
861  pointer to its abstract value, or nullptr if the port is not connected. `func`
862  should be the user-visible API function name obtained with __func__. */
863  const AbstractValue* EvalAbstractInputImpl(const char* func,
864  const ContextBase& context,
865  InputPortIndex port_index) const;
866 
867  /** Throws std::out_of_range to report a negative `port_index` that was
868  passed to API method `func`. Caller must ensure that the function name
869  makes it clear what kind of port we're complaining about. */
870  // We're taking an int here for the index; InputPortIndex and OutputPortIndex
871  // can't be negative.
872  [[noreturn]] void ThrowNegativePortIndex(const char* func,
873  int port_index) const;
874 
875  /** Throws std::out_of_range to report bad input `port_index` that was passed
876  to API method `func`. */
877  [[noreturn]] void ThrowInputPortIndexOutOfRange(
878  const char* func, InputPortIndex port_index) const;
879 
880  /** Throws std::out_of_range to report bad output `port_index` that was passed
881  to API method `func`. */
882  [[noreturn]] void ThrowOutputPortIndexOutOfRange(
883  const char* func, OutputPortIndex port_index) const;
884 
885  /** Throws std::logic_error because someone misused API method `func`, that is
886  only allowed for declared-vector input ports, on an abstract port whose
887  index is given here. */
888  [[noreturn]] void ThrowNotAVectorInputPort(const char* func,
889  InputPortIndex port_index) const;
890 
891  /** Throws std::logic_error because someone called API method `func` claiming
892  the input port had some value type that was wrong. */
893  [[noreturn]] void ThrowInputPortHasWrongType(
894  const char* func, InputPortIndex port_index,
895  const std::string& expected_type, const std::string& actual_type) const;
896 
897  /** Throws std::logic_error because someone called API method `func`, that
898  requires this input port to be evaluatable, but the port was neither
899  fixed nor connected. */
900  [[noreturn]] void ThrowCantEvaluateInputPort(const char* func,
901  InputPortIndex port_index) const;
902 
903  /** (Internal use only) Returns the InputPortBase at index `port_index`,
904  throwing std::out_of_range we don't like the port index. The name of the
905  public API method that received the bad index is provided in `func` and is
906  included in the error message. */
907  const InputPortBase& GetInputPortBaseOrThrow(const char* func,
908  int port_index) const {
909  if (port_index < 0)
910  ThrowNegativePortIndex(func, port_index);
911  const InputPortIndex port(port_index);
912  if (port_index >= get_num_input_ports())
913  ThrowInputPortIndexOutOfRange(func, port);
914  return *input_ports_[port];
915  }
916 
917  /** (Internal use only) Returns the OutputPortBase at index `port_index`,
918  throwing std::out_of_range we don't like the port index. The name of the
919  public API method that received the bad index is provided in `func` and is
920  included in the error message. */
921  const OutputPortBase& GetOutputPortBaseOrThrow(const char* func,
922  int port_index) const {
923  if (port_index < 0)
924  ThrowNegativePortIndex(func, port_index);
925  const OutputPortIndex port(port_index);
926  if (port_index >= get_num_output_ports())
927  ThrowOutputPortIndexOutOfRange(func, port);
928  return *output_ports_[port_index];
929  }
930 
931  /** This method must be invoked from within derived class DoAllocateContext()
932  implementations right after the concrete Context object has been allocated.
933  It allocates cache entries, sets up all intra-Context dependencies, and marks
934  the ContextBase as initialized so that we can verify proper derived-class
935  behavior.
936  @pre The supplied context must not be null and must not already have been
937  initialized. */
938  void InitializeContextBase(ContextBase* context) const;
939 
940  /** Derived class implementations should allocate a suitable concrete Context
941  type, then invoke the above InitializeContextBase() method. A Diagram must
942  then invoke AllocateContext() to obtain each of the subcontexts for its
943  DiagramContext, and must set up inter-subcontext dependencies among its
944  children and between itself and its children. Then context resources such as
945  parameters and state should be allocated. */
946  virtual std::unique_ptr<ContextBase> DoAllocateContext() const = 0;
947 
948  /** Derived classes must implement this to verify that the supplied
949  Context is suitable, and throw an exception if not. This is a runtime check
950  but may be expensive so is not guaranteed to be invoked except in Debug
951  builds. */
952  virtual void DoCheckValidContext(const ContextBase&) const = 0;
953 
954  private:
955  void CreateSourceTrackers(ContextBase*) const;
956 
957  // Used to create trackers for variable-number System-allocated objects.
958  struct TrackerInfo {
959  DependencyTicket ticket;
960  std::string description;
961  };
962 
963  const TrackerInfo& discrete_state_tracker_info(
964  DiscreteStateIndex index) const {
965  DRAKE_DEMAND(0 <= index && index < num_discrete_state_groups());
966  return discrete_state_tickets_[index];
967  }
968 
969  const TrackerInfo& abstract_state_tracker_info(
970  AbstractStateIndex index) const {
971  DRAKE_DEMAND(0 <= index && index < num_abstract_states());
972  return abstract_state_tickets_[index];
973  }
974 
975  const TrackerInfo& numeric_parameter_tracker_info(
976  NumericParameterIndex index) const {
977  DRAKE_DEMAND(0 <= index && index < num_numeric_parameters());
978  return numeric_parameter_tickets_[index];
979  }
980 
981  const TrackerInfo& abstract_parameter_tracker_info(
982  AbstractParameterIndex index) const {
983  DRAKE_DEMAND(0 <= index && index < num_abstract_parameters());
984  return abstract_parameter_tickets_[index];
985  }
986 
987  // Ports and cache entries hold their own DependencyTickets. Note that the
988  // addresses of the elements are stable even if the std::vectors are resized.
989 
990  // Indexed by InputPortIndex.
991  std::vector<std::unique_ptr<InputPortBase>> input_ports_;
992  // Indexed by OutputPortIndex.
993  std::vector<std::unique_ptr<OutputPortBase>> output_ports_;
994  // Indexed by CacheIndex.
995  std::vector<std::unique_ptr<CacheEntry>> cache_entries_;
996 
997  // States and parameters don't hold their own tickets so we track them here.
998 
999  // Indexed by DiscreteStateIndex.
1000  std::vector<TrackerInfo> discrete_state_tickets_;
1001  // Indexed by AbstractStateIndex.
1002  std::vector<TrackerInfo> abstract_state_tickets_;
1003  // Indexed by NumericParameterIndex.
1004  std::vector<TrackerInfo> numeric_parameter_tickets_;
1005  // Indexed by AbstractParameterIndex.
1006  std::vector<TrackerInfo> abstract_parameter_tickets_;
1007 
1008  // Initialize to the first ticket number available after all the well-known
1009  // ones. This gets incremented as tickets are handed out for the optional
1010  // entities above.
1011  DependencyTicket next_available_ticket_{internal::kNextAvailableTicket};
1012 
1013  // The enclosing Diagram. Null/invalid when this is the root system.
1014  const internal::SystemParentServiceInterface* parent_service_{nullptr};
1015 
1016  // Name of this system.
1017  std::string name_;
1018 };
1019 
1020 // Implementations of templatized DeclareCacheEntry() methods.
1021 
1022 // Takes make() and calc() member functions.
1023 template <class MySystem, class MyContext, typename ValueType>
1025  std::string description,
1026  ValueType (MySystem::*make)() const,
1027  void (MySystem::*calc)(const MyContext&, ValueType*) const,
1028  std::set<DependencyTicket> prerequisites_of_calc) {
1030  "Expected to be invoked from a SystemBase-derived System.");
1032  "Expected to be invoked with a ContextBase-derived Context.");
1033  auto this_ptr = dynamic_cast<const MySystem*>(this);
1034  DRAKE_DEMAND(this_ptr != nullptr);
1035  auto alloc_callback = [this_ptr, make]() {
1036  return AbstractValue::Make((this_ptr->*make)());
1037  };
1038  auto calc_callback = [this_ptr, calc](const ContextBase& context,
1039  AbstractValue* result) {
1040  const auto& typed_context = dynamic_cast<const MyContext&>(context);
1041  ValueType& typed_result = result->GetMutableValue<ValueType>();
1042  (this_ptr->*calc)(typed_context, &typed_result);
1043  };
1044  // Invoke the general signature above.
1045  auto& entry = DeclareCacheEntry(
1046  std::move(description), std::move(alloc_callback),
1047  std::move(calc_callback), std::move(prerequisites_of_calc));
1048  return entry;
1049 }
1050 
1051 // Takes an initial value and calc() member function that has an output
1052 // argument.
1053 template <class MySystem, class MyContext, typename ValueType>
1055  std::string description, const ValueType& model_value,
1056  void (MySystem::*calc)(const MyContext&, ValueType*) const,
1057  std::set<DependencyTicket> prerequisites_of_calc) {
1059  "Expected to be invoked from a SystemBase-derived System.");
1061  "Expected to be invoked with a ContextBase-derived Context.");
1062  auto this_ptr = dynamic_cast<const MySystem*>(this);
1063  DRAKE_DEMAND(this_ptr != nullptr);
1064  // The given model value may have *either* a copy constructor or a Clone()
1065  // method, since it just has to be suitable for containing in an
1066  // AbstractValue. We need to create a functor that is copy constructible,
1067  // so need to wrap the model value to give it a copy constructor. Drake's
1068  // copyable_unique_ptr does just that, so is suitable for capture by the
1069  // allocator functor here.
1071  std::make_unique<Value<ValueType>>(model_value));
1072  auto alloc_callback = [model = std::move(owned_model)]() {
1073  return model->Clone();
1074  };
1075  auto calc_callback = [this_ptr, calc](const ContextBase& context,
1076  AbstractValue* result) {
1077  const auto& typed_context = dynamic_cast<const MyContext&>(context);
1078  ValueType& typed_result = result->GetMutableValue<ValueType>();
1079  (this_ptr->*calc)(typed_context, &typed_result);
1080  };
1081  auto& entry = DeclareCacheEntry(
1082  std::move(description), std::move(alloc_callback),
1083  std::move(calc_callback), std::move(prerequisites_of_calc));
1084  return entry;
1085 }
1086 
1087 // Takes an initial value and value-returning calc() member function.
1088 // See the above output-argument signature for an explanation of the code.
1089 // TODO(sherm1) Consider whether common code in this and the previous method
1090 // can be factored out and shared rather than repeated.
1091 template <class MySystem, class MyContext, typename ValueType>
1093  std::string description, const ValueType& model_value,
1094  ValueType (MySystem::*calc)(const MyContext&) const,
1095  std::set<DependencyTicket> prerequisites_of_calc) {
1097  "Expected to be invoked from a SystemBase-derived System.");
1099  "Expected to be invoked with a ContextBase-derived Context.");
1100  auto this_ptr = dynamic_cast<const MySystem*>(this);
1101  DRAKE_DEMAND(this_ptr != nullptr);
1103  std::make_unique<Value<ValueType>>(model_value));
1104  auto alloc_callback = [model = std::move(owned_model)]() {
1105  return model->Clone();
1106  };
1107  auto calc_callback = [this_ptr, calc](const ContextBase& context,
1108  AbstractValue* result) {
1109  const auto& typed_context = dynamic_cast<const MyContext&>(context);
1110  ValueType& typed_result = result->GetMutableValue<ValueType>();
1111  typed_result = (this_ptr->*calc)(typed_context);
1112  };
1113  auto& entry = DeclareCacheEntry(
1114  std::move(description), std::move(alloc_callback),
1115  std::move(calc_callback), std::move(prerequisites_of_calc));
1116  return entry;
1117 }
1118 
1119 // Takes just a calc() member function with an output argument, and
1120 // value-initializes the entry.
1121 template <class MySystem, class MyContext, typename ValueType>
1123  std::string description,
1124  void (MySystem::*calc)(const MyContext&, ValueType*) const,
1125  std::set<DependencyTicket> prerequisites_of_calc) {
1126  static_assert(
1128  "SystemBase::DeclareCacheEntry(calc): the calc-only overloads of "
1129  "this method requires that the output type has a default constructor");
1130  // Invokes the above model-value method. Note that value initialization {}
1131  // is required here.
1132  return DeclareCacheEntry(std::move(description), ValueType{}, calc,
1133  std::move(prerequisites_of_calc));
1134 }
1135 
1136 // Takes just a value-returning calc() member function, and
1137 // value-initializes the entry. See previous method for more information.
1138 template <class MySystem, class MyContext, typename ValueType>
1140  std::string description,
1141  ValueType (MySystem::*calc)(const MyContext&) const,
1142  std::set<DependencyTicket> prerequisites_of_calc) {
1143  static_assert(
1145  "SystemBase::DeclareCacheEntry(calc): the calc-only overloads of "
1146  "this method requires that the output type has a default constructor");
1147  return DeclareCacheEntry(std::move(description), ValueType{}, calc,
1148  std::move(prerequisites_of_calc));
1149 }
1150 
1151 } // namespace systems
1152 } // namespace drake
OutputPortBase handles the scalar type-independent aspects of an OutputPort.
Definition: output_port_base.h:16
DependencyTicket numeric_parameter_ticket(NumericParameterIndex index) const
Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector)...
Definition: system_base.h:577
const OutputPortBase & get_output_port_base(OutputPortIndex port_index) const
Returns a reference to an OutputPort given its port_index.
Definition: system_base.h:190
const OutputPortBase & GetOutputPortBaseOrThrow(const char *func, int port_index) const
(Internal use only) Returns the OutputPortBase at index port_index, throwing std::out_of_range we don...
Definition: system_base.h:921
const InputPortBase & GetInputPortBaseOrThrow(const char *func, int port_index) const
(Internal use only) Returns the InputPortBase at index port_index, throwing std::out_of_range we don&#39;...
Definition: system_base.h:907
void AddNumericParameter(NumericParameterIndex index)
(Internal use only) Assigns a ticket to a new numeric parameter with the given index.
Definition: system_base.h:803
static DependencyTicket xcdot_ticket()
Returns a ticket for the cache entry that holds time derivatives of the continuous variables...
Definition: system_base.h:683
double value
Definition: wrap_test_util_py.cc:12
int num_abstract_states() const
Returns the number of declared abstract state variables.
Definition: system_base.h:731
void InitializeContextBase(ContextBase *context) const
This method must be invoked from within derived class DoAllocateContext() implementations right after...
Definition: system_base.cc:55
void AddInputPort(std::unique_ptr< InputPortBase > port)
(Internal use only) Adds an already-constructed input port to this System.
Definition: system_base.h:757
static DependencyTicket pnc_ticket()
Returns a ticket for the cache entry that holds the non-conservative power calculation.
Definition: system_base.h:711
Provides a convenient wrapper to throw an exception when a condition is unmet.
int get_num_output_ports() const
Returns the number of output ports currently allocated in this System.
Definition: system_base.h:178
DependencyTicket input_port_ticket(InputPortIndex index)
Returns a ticket indicating dependence on input port uᵢ indicated by index.
Definition: system_base.h:614
Definition: bullet_model.cc:22
static DependencyTicket xa_ticket()
Returns a ticket indicating dependence on all of the abstract state variables in the current Context...
Definition: system_base.h:560
static DependencyTicket all_parameters_ticket()
Returns a ticket indicating dependence on all parameters p in this system, including numeric paramete...
Definition: system_base.h:607
virtual std::unique_ptr< ContextBase > DoAllocateContext() const =0
Derived class implementations should allocate a suitable concrete Context type, then invoke the above...
int get_num_total_outputs() const
Returns the total dimension of all of the vector-valued output ports (as if they were muxed)...
Definition: system_base.h:204
void ThrowCantEvaluateInputPort(const char *func, InputPortIndex port_index) const
Throws std::logic_error because someone called API method func, that requires this input port to be e...
Definition: system_base.cc:229
static DependencyTicket all_state_ticket()
Returns a ticket indicating dependence on all state variables x in this system, including continuous ...
Definition: system_base.h:570
DependencyTicket cache_entry_ticket(CacheIndex index)
Returns a ticket indicating dependence on the cache entry indicated by index.
Definition: system_base.h:639
void AddAbstractState(AbstractStateIndex index)
(Internal use only) Assigns a ticket to a new abstract state variable with the given index...
Definition: system_base.h:792
~SystemBase() override
Definition: system_base.cc:19
int num_numeric_parameters() const
Returns the number of declared numeric parameters (each of these is a vector-valued parameter)...
Definition: system_base.h:737
void AddAbstractParameter(AbstractParameterIndex index)
(Internal use only) Assigns a ticket to a new abstract parameter with the given index.
Definition: system_base.h:814
const InputPortBase & get_input_port_base(InputPortIndex port_index) const
Returns a reference to an InputPort given its port_index.
Definition: system_base.h:184
void CheckValidContext(const ContextBase &context) const
Checks whether the given context is valid for this System and throws an exception with a helpful mess...
Definition: system_base.h:448
std::function< void(const ContextBase &, AbstractValue *)> CalcCallback
Signature of a function suitable for calculating a value of a particular cache entry, given a place to put the value.
Definition: cache_entry.h:57
void AddOutputPort(std::unique_ptr< OutputPortBase > port)
(Internal use only) Adds an already-constructed output port to this System.
Definition: system_base.h:770
DependencyTicket abstract_state_ticket(AbstractStateIndex index) const
Returns a ticket indicating dependence on a particular abstract state variable xaᵢ.
Definition: system_base.h:552
DependencyTicket output_port_ticket(OutputPortIndex index)
(Internal use only) Returns a ticket indicating dependence on the output port indicated by index...
Definition: system_base.h:719
std::string to_string(const drake::geometry::Identifier< Tag > &id)
Enables use of identifiers with to_string.
Definition: identifier.h:215
static DependencyTicket all_input_ports_ticket()
Returns a ticket indicating dependence on all input ports u of this system.
Definition: system_base.h:622
int get_num_total_inputs() const
Returns the total dimension of all of the vector-valued input ports (as if they were muxed)...
Definition: system_base.h:196
const CacheEntry & DeclareCacheEntryWithKnownTicket(DependencyTicket known_ticket, std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
(Internal use only) This is for cache entries associated with pre-defined tickets, for example the cache entry for time derivatives.
Definition: system_base.cc:39
std::string GetNiceTypeName() const
Returns a human-readable name for the underlying type T.
Definition: value.h:128
void ThrowNegativePortIndex(const char *func, int port_index) const
Throws std::out_of_range to report a negative port_index that was passed to API method func...
Definition: system_base.cc:186
std::vector< Number > result
Definition: ipopt_solver.cc:151
Provides non-templatized Context functionality shared by the templatized derived classes.
Definition: context_base.h:38
static DependencyTicket pc_ticket()
Returns a ticket for the cache entry that holds the conservative power calculation.
Definition: system_base.h:704
int num_cache_entries() const
Returns the number nc of cache entries currently allocated in this System.
Definition: system_base.h:212
#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
std::function< std::unique_ptr< AbstractValue >()> AllocCallback
Signature of a function suitable for allocating an object that can hold a value of a particular cache...
Definition: cache_entry.h:53
void ThrowOutputPortIndexOutOfRange(const char *func, OutputPortIndex port_index) const
Throws std::out_of_range to report bad output port_index that was passed to API method func...
Definition: system_base.cc:202
static DependencyTicket xc_ticket()
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z.
Definition: system_base.h:529
static DependencyTicket pn_ticket()
Returns a ticket indicating dependence on all of the numerical parameters in the current Context...
Definition: system_base.h:585
const std::string & GetSystemName() const final
Returns a human-readable name for this system, for use in messages and logging.
Definition: system_base.h:56
#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 DoCheckValidContext(const ContextBase &) const =0
Derived classes must implement this to verify that the supplied Context is suitable, and throw an exception if not.
const T * MaybeGetValue() const
Like GetValue, but quietly returns nullptr on mismatched types, even in Release builds.
Definition: value.h:158
void ThrowNotAVectorInputPort(const char *func, InputPortIndex port_index) const
Throws std::logic_error because someone misused API method func, that is only allowed for declared-ve...
Definition: system_base.cc:210
static DependencyTicket accuracy_ticket()
Returns a ticket indicating dependence on the accuracy setting in the Context.
Definition: system_base.h:501
Provides non-templatized functionality shared by the templatized System classes.
Definition: system_base.h:29
std::unique_ptr< ContextBase > AllocateContext() const
Returns a Context suitable for use with this System.
Definition: system_base.h:84
const std::string & get_name() const
Returns the name last supplied to set_name(), if any.
Definition: system_base.h:50
A fully type-erased container class.
Definition: value.h:101
const AbstractValue * EvalAbstractInput(const ContextBase &context, int port_index) const
Returns the value of the input port with the given port_index as an AbstractValue, which is permitted for ports of any type.
Definition: system_base.h:127
static std::unique_ptr< AbstractValue > Make(const T &value)
Returns an AbstractValue containing the given value.
Definition: value.h:201
void ThrowInputPortIndexOutOfRange(const char *func, InputPortIndex port_index) const
Throws std::out_of_range to report bad input port_index that was passed to API method func...
Definition: system_base.cc:194
static DependencyTicket ke_ticket()
Returns a ticket for the cache entry that holds the kinetic energy calculation.
Definition: system_base.h:697
static DependencyTicket q_ticket()
Returns a ticket indicating that a computation depends on configuration state variables q...
Definition: system_base.h:508
static void set_parent_service(SystemBase *child, const internal::SystemParentServiceInterface *parent_service)
(Internal use only) Declares that parent_service is the service interface of the Diagram that owns th...
Definition: system_base.h:851
static DependencyTicket configuration_ticket()
Returns a ticket indicating dependence on all source values that may affect configuration-dependent c...
Definition: system_base.h:662
void AddDiscreteStateGroup(DiscreteStateIndex index)
(Internal use only) Assigns a ticket to a new discrete variable group with the given index...
Definition: system_base.h:781
static DependencyTicket time_ticket()
Returns a ticket indicating dependence on time.
Definition: system_base.h:494
void ThrowInputPortHasWrongType(const char *func, InputPortIndex port_index, const std::string &expected_type, const std::string &actual_type) const
Throws std::logic_error because someone called API method func claiming the input port had some value...
Definition: system_base.cc:220
const std::string description
Definition: proximity_engine_test.cc:721
int get_num_input_ports() const
Returns the number of input ports currently allocated in this System.
Definition: system_base.h:172
DependencyTicket abstract_parameter_ticket(AbstractParameterIndex index) const
Returns a ticket indicating dependence on a particular abstract parameter paᵢ.
Definition: system_base.h:592
int num_discrete_state_groups() const
Returns the number of declared discrete state groups (each group is a vector-valued discrete state va...
Definition: system_base.h:726
std::string GetSystemPathname() const final
Generates and returns a human-readable full path name of this subsystem, for use in messages and logg...
Definition: system_base.cc:21
void ThrowIfContextNotCompatible(const ContextBase &context) const final
Throws an exception with an appropriate message if the given context is not compatible with this Syst...
Definition: system_base.h:77
const V * EvalInputValue(const ContextBase &context, int port_index) const
Returns the value of an abstract-valued input port with the given port_index as a value of known type...
Definition: system_base.h:149
const CacheEntry & get_cache_entry(CacheIndex index) const
Return a reference to a CacheEntry given its index.
Definition: system_base.h:217
DependencyTicket assign_next_dependency_ticket()
(Internal use only) Assigns the next unused dependency ticket number, unique only within a particular...
Definition: system_base.h:841
std::string GetSystemType() const final
Returns the most-derived type of this concrete System object as a human-readable string suitable for ...
Definition: system_base.h:71
const AbstractValue * EvalAbstractInputImpl(const char *func, const ContextBase &context, InputPortIndex port_index) const
(Internal use only) Shared code for updating an input port and returning a pointer to its abstract va...
Definition: system_base.cc:163
TypeSafeIndex< class DependencyTag > DependencyTicket
Identifies a particular source value or computation for purposes of declaring and managing dependenci...
Definition: framework_common.h:26
static DependencyTicket nothing_ticket()
Returns a ticket indicating that a computation does not depend on any source value; that is...
Definition: system_base.h:488
void set_name(const std::string &name)
Sets the name of the system.
Definition: system_base.h:40
static DependencyTicket z_ticket()
Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables ...
Definition: system_base.h:523
A container class for an arbitrary type T.
Definition: value.h:252
static DependencyTicket v_ticket()
Returns a ticket indicating dependence on velocity state variables v.
Definition: system_base.h:516
int num_abstract_parameters() const
Returns the number of declared abstract parameters.
Definition: system_base.h:742
static DependencyTicket all_sources_ticket()
Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries).
Definition: system_base.h:631
static DependencyTicket pe_ticket()
Returns a ticket for the cache entry that holds the potential energy calculation. ...
Definition: system_base.h:690
static const std::string & Get()
Attempts to return a nicely demangled and canonicalized type name that is the same on all platforms...
Definition: nice_type_name.h:53
#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
DependencyTicket discrete_state_ticket(DiscreteStateIndex index) const
Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector)...
Definition: system_base.h:537
std::string name
Definition: geometry_base_test.cc:343
A smart pointer with deep copy semantics.
Definition: copyable_unique_ptr.h:107
const internal::SystemParentServiceInterface * get_parent_service() const
Returns a pointer to the service interface of the immediately enclosing Diagram if one has been set...
Definition: system_base.h:834
static DependencyTicket pa_ticket()
Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context...
Definition: system_base.h:601
const char * func
Definition: drake_throw.h:16
const CacheEntry & DeclareCacheEntry(std::string description, CacheEntry::AllocCallback alloc_function, CacheEntry::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
Declares a new CacheEntry in this System using the least-restrictive definitions for the associated f...
Definition: system_base.cc:29
static DependencyTicket kinematics_ticket()
Returns a ticket indicating dependence on all source values that may affect configuration- or velocit...
Definition: system_base.h:676
static DependencyTicket xd_ticket()
Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group.
Definition: system_base.h:545
An InputPort is a System resource that describes the kind of input a System accepts, on a given port.
Definition: input_port_base.h:22
SystemBase()=default
(Internal use only) Default constructor.
A CacheEntry belongs to a System and represents the properties of one of that System&#39;s cached computa...
Definition: cache_entry.h:42