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  /** Declares a new %CacheEntry in this System using the least-restrictive
302  definitions for the associated functions. Prefer one of the more-convenient
303  signatures below if you can. The new cache entry is assigned a unique
304  CacheIndex and DependencyTicket, which can be obtained from the returned
305  %CacheEntry. The function signatures here are:
306  @code
307  std::unique_ptr<AbstractValue> Alloc();
308  void Calc(const ContextBase&, AbstractValue*);
309  @endcode
310  where the AbstractValue objects must resolve to the same concrete type.
311 
312  @param[in] description
313  A human-readable description of this cache entry, most useful for debugging
314  and documentation. Not interpreted in any way by Drake; it is retained
315  by the cache entry and used to generate the description for the
316  corresponding CacheEntryValue in the Context.
317  @param[in] alloc_function
318  Given a Context, returns a heap-allocated AbstractValue object suitable for
319  holding a value for this cache entry.
320  @param[in] calc_function
321  Provides the computation that maps from a given Context to the current
322  value that this cache entry should have, and writes that value to a given
323  object of the type returned by `alloc_function`.
324  @param[in] prerequisites_of_calc
325  Provides the DependencyTicket list containing a ticket for _every_ Context
326  value on which `calc_function` may depend when it computes its result.
327  Defaults to `{all_sources_ticket()}` if unspecified. If the cache value
328  is truly independent of the Context (rare!) say so explicitly by providing
329  the list `{nothing_ticket()}`; an explicitly empty list `{}` is forbidden.
330  @returns a const reference to the newly-created %CacheEntry.
331  @throws std::logic_error if given an explicitly empty prerequisite list. */
332  // Arguments to these methods are moved from internally. Taking them by value
333  // rather than reference avoids a copy when the original argument is
334  // an rvalue.
336  std::string description, CacheEntry::AllocCallback alloc_function,
337  CacheEntry::CalcCallback calc_function,
338  std::set<DependencyTicket> prerequisites_of_calc = {
339  all_sources_ticket()});
340 
341  /** Declares a cache entry by specifying member functions to use both for the
342  allocator and calculator. The signatures are: @code
343  ValueType MySystem::MakeValueType() const;
344  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
345  @endcode
346  where `MySystem` is a class derived from `SystemBase`, `MyContext` is a class
347  derived from `ContextBase`, and `ValueType` is any concrete type such that
348  `Value<ValueType>` is permitted. (The method names are arbitrary.) Template
349  arguments will be deduced and do not need to be specified. See the first
350  DeclareCacheEntry() signature above for more information about the parameters
351  and behavior.
352  @see drake::systems::Value */
353  template <class MySystem, class MyContext, typename ValueType>
355  std::string description,
356  ValueType (MySystem::*make)() const,
357  void (MySystem::*calc)(const MyContext&, ValueType*) const,
358  std::set<DependencyTicket> prerequisites_of_calc = {
359  all_sources_ticket()});
360 
361  /** Declares a cache entry by specifying a model value of concrete type
362  `ValueType` and a calculator function that is a class member function (method)
363  with signature: @code
364  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
365  @endcode
366  where `MySystem` is a class derived from `SystemBase`, `MyContext` is a class
367  derived from `ContextBase`, and `ValueType` is any concrete type such that
368  `Value<ValueType>` is permitted. (The method names are arbitrary.) Template
369  arguments will be deduced and do not need to be specified.
370  See the first DeclareCacheEntry() signature above for more information about
371  the parameters and behavior.
372  @see drake::systems::Value */
373  template <class MySystem, class MyContext, typename ValueType>
375  std::string description, const ValueType& model_value,
376  void (MySystem::*calc)(const MyContext&, ValueType*) const,
377  std::set<DependencyTicket> prerequisites_of_calc = {
378  all_sources_ticket()});
379 
380  /** Declares a cache entry by specifying only a calculator function that is a
381  class member function (method) with signature:
382  @code
383  void MySystem::CalcCacheValue(const MyContext&, ValueType*) const;
384  @endcode
385  where `MySystem` is a class derived from `SystemBase` and `MyContext` is a
386  class derived from `ContextBase`. `ValueType` is a concrete type such that
387  (a) `Value<ValueType>` is permitted, and (b) `ValueType` is default
388  constructible. That allows us to create a model value using
389  `Value<ValueType>{}` (value initialized so numerical types will be zeroed in
390  the model). (The method name is arbitrary.) Template arguments will be
391  deduced and do not need to be specified. See the first DeclareCacheEntry()
392  signature above for more information about the parameters and behavior.
393 
394  @note The default constructor will be called once immediately to create a
395  model value, and subsequent allocations will just copy the model value without
396  invoking the constructor again. If you want the constructor invoked again at
397  each allocation (not common), use one of the other signatures to explicitly
398  provide a method for the allocator to call; that method can then invoke
399  the `ValueType` default constructor each time it is called.
400  @see drake::systems::Value */
401  template <class MySystem, class MyContext, typename ValueType>
403  std::string description,
404  void (MySystem::*calc)(const MyContext&, ValueType*) const,
405  std::set<DependencyTicket> prerequisites_of_calc = {
406  all_sources_ticket()});
407  //@}
408 
409  /** Checks whether the given context is valid for this System and throws
410  an exception with a helpful message if not. This is *very* expensive and
411  should generally be done only in Debug builds, like this:
412  @code
413  DRAKE_ASSERT_VOID(CheckValidContext(context));
414  @endcode */
415  void CheckValidContext(const ContextBase& context) const {
416  // TODO(sherm1) Add base class checks.
417 
418  // Let derived classes have their say.
419  DoCheckValidContext(context);
420  }
421 
422  //============================================================================
423  /** @name Dependency tickets
424  @anchor DependencyTicket_documentation
425 
426  Use these tickets to declare well-known sources as prerequisites of a
427  downstream computation such as an output port, derivative, update, or cache
428  entry. The ticket numbers for these sources are the same for all systems.
429  For time and accuracy they refer to the same global resource; otherwise they
430  refer to the specified sources within the referencing system.
431 
432  A dependency ticket for a more specific resource (a particular input or
433  output port, a discrete variable group, abstract state variable, a parameter,
434  or a cache entry) is allocated and stored with the resource when it is
435  declared. Usually the tickets are obtained directly from the resource but
436  you can recover them with methods here knowing only the resource index. */
437  //@{
438 
439  // The DependencyTrackers associated with these tickets are allocated
440  // in ContextBase::CreateBuiltInTrackers() and the implementation there must
441  // be kept up to date with the API contracts here.
442 
443  /** Returns a ticket indicating dependence on every possible independent
444  source value, including time, state, input ports, parameters, and the accuracy
445  setting (but not cache entries). This is the default dependency for
446  computations that have not specified anything more refined. */
448  return DependencyTicket(internal::kAllSourcesTicket);
449  }
450 
451  /** Returns a ticket indicating that a computation does not depend on *any*
452  source value; that is, it is a constant. If this appears in a prerequisite
453  list, it must be the only entry. */
455  return DependencyTicket(internal::kNothingTicket);
456  }
457 
458  /** Returns a ticket indicating dependence on time. This is the same ticket
459  for all systems and refers to the same time value. */
461  return DependencyTicket(internal::kTimeTicket);
462  }
463 
464  /** Returns a ticket indicating dependence on the accuracy setting in the
465  Context. This is the same ticket for all systems and refers to the same
466  accuracy value. */
468  return DependencyTicket(internal::kAccuracyTicket);
469  }
470 
471  /** Returns a ticket indicating that a computation depends on configuration
472  state variables q. */
474  return DependencyTicket(internal::kQTicket);
475  }
476 
477  /** Returns a ticket indicating dependence on velocity state variables v. This
478  does _not_ also indicate a dependence on configuration variables q -- you must
479  list that explicitly or use kinematics_ticket() instead. */
481  return DependencyTicket(internal::kVTicket);
482  }
483 
484  /** Returns a ticket indicating dependence on all of the miscellaneous
485  continuous state variables z. */
487  return DependencyTicket(internal::kZTicket);
488  }
489 
490  /** Returns a ticket indicating dependence on all of the continuous
491  state variables q, v, or z. */
493  return DependencyTicket(internal::kXcTicket);
494  }
495 
496  /** Returns a ticket indicating dependence on all of the numerical
497  discrete state variables, in any discrete variable group. */
499  return DependencyTicket(internal::kXdTicket);
500  }
501 
502  /** Returns a ticket indicating dependence on all of the abstract
503  state variables in the current Context. */
505  return DependencyTicket(internal::kXaTicket);
506  }
507 
508  /** Returns a ticket indicating dependence on _all_ state variables x in this
509  system, including continuous variables xc, discrete (numeric) variables xd,
510  and abstract state variables xa. This does not imply dependence on time,
511  parameters, or inputs; those must be specified separately. If you mean to
512  express dependence on all possible value sources, use all_sources_ticket()
513  instead. */
515  return DependencyTicket(internal::kXTicket);
516  }
517 
518  /** Returns a ticket for the cache entry that holds time derivatives of
519  the continuous variables. */
521  return DependencyTicket(internal::kXcdotTicket);
522  }
523 
524  /** Returns a ticket for the cache entry that holds the discrete state
525  update for the numerical discrete variables in the state. */
527  return DependencyTicket(internal::kXdhatTicket);
528  }
529 
530  /** Returns a ticket indicating dependence on all the configuration
531  variables for this System. By default this is set to the continuous
532  second-order state variables q, but configuration may be represented
533  differently in some systems (discrete ones, for example), in which case this
534  ticket should have been set to depend on that representation. This ticket
535  also assumes that configuration computations may depend on any parameter and
536  on the accuracy setting (which don't change often), but not on time.
537  Examples: a parameter that affects length may change the computation of an
538  end-effector location. A change in accuracy requirement may require
539  recomputation of an iterative approximation of contact forces. */
540  // The configuration_tracker implementation in ContextBase must be kept
541  // up to date with the above API contract.
543  return DependencyTicket(internal::kConfigurationTicket);
544  }
545 
546  /** (Advanced) Returns a ticket indicating dependence on all of the velocity
547  variables, but _not_ the configuration variables for this System. By default
548  this is set to the continuous state variables v, but velocity may be
549  represented differently in some systems (discrete ones, for example), in which
550  case this ticket should have been set to depend on that representation. This
551  ticket also assumes that velocity calculations may depend on any parameter and
552  on the accuracy setting (which don't change often), but not on time.
553  Examples: a parameter that affects length may change the computation of an
554  end-effector velocity. A change in accuracy requirement may require
555  recomputation of an iterative approximation of friction forces.
556 
557  @warning This _does not_ include dependence on configuration, although
558  most velocity calculations do depend on configuration. If you want to
559  register dependence on both (more common), use kinematics_ticket(). */
560  // The velocity_tracker implementation in ContextBase must be kept
561  // up to date with the above API contract.
563  return DependencyTicket(internal::kVelocityTicket);
564  }
565 
566  /** Returns a ticket indicating dependence on all of the configuration
567  and velocity state variables of this System. This ticket depends on the
568  configuration_ticket and the velocity_ticket. Note that this includes
569  dependence on all parameters and the accuracy setting, but not on time.
570  @see configuration_ticket(), velocity_ticket() */
572  return DependencyTicket(internal::kKinematicsTicket);
573  }
574 
575  /** Returns a ticket indicating dependence on _all_ parameters p in this
576  system, including numeric parameters pn, and abstract parameters pa. */
578  return DependencyTicket(internal::kAllParametersTicket);
579  }
580 
581  /** Returns a ticket indicating dependence on _all_ input ports u of this
582  system. */
584  return DependencyTicket(internal::kAllInputPortsTicket);
585  }
586 
587  /** Returns a ticket indicating dependence on the input port indicated
588  by `index`.
589  @pre `index` selects an existing input port of this System. */
591  DRAKE_DEMAND(0 <= index && index < get_num_input_ports());
592  return input_ports_[index]->ticket();
593  }
594 
595  /** Returns a ticket indicating dependence on the output port indicated
596  by `index`.
597  @pre `index` selects an existing output port of this System. */
599  DRAKE_DEMAND(0 <= index && index < get_num_output_ports());
600  return output_ports_[index]->ticket();
601  }
602 
603  /** Returns a ticket indicating dependence on the cache entry indicated
604  by `index`.
605  @pre `index` selects an existing cache entry in this System. */
607  DRAKE_DEMAND(0 <= index && index < num_cache_entries());
608  return cache_entries_[index]->ticket();
609  }
610 
611  /** Returns the number of declared discrete state groups (each group is
612  a vector-valued discrete state variable). */
614  return static_cast<int>(discrete_state_tickets_.size());
615  }
616 
617  /** Returns the number of declared abstract state variables. */
618  int num_abstract_states() const {
619  return static_cast<int>(abstract_state_tickets_.size());
620  }
621 
622  /** Returns the number of declared numeric parameters (each of these is
623  a vector-valued parameter). */
625  return static_cast<int>(numeric_parameter_tickets_.size());
626  }
627 
628  /** Returns the number of declared abstract parameters. */
630  return static_cast<int>(abstract_parameter_tickets_.size());
631  }
632 
633  /** Returns a ticket indicating dependence on a particular discrete state
634  variable (may be a vector). (We sometimes refer to this as a "discrete
635  variable group".) */
637  return discrete_state_tracker_info(index).ticket;
638  }
639 
640  /** Returns a ticket indicating dependence on a particular abstract state
641  variable. */
643  return abstract_state_tracker_info(index).ticket;
644  }
645 
646  /** Returns a ticket indicating dependence on a particular numeric parameter
647  (may be a vector). */
649  return numeric_parameter_tracker_info(index).ticket;
650  }
651 
652  /** Returns a ticket indicating dependence on a particular abstract
653  parameter. */
655  AbstractParameterIndex index) const {
656  return abstract_parameter_tracker_info(index).ticket;
657  }
658  //@}
659 
660  protected:
661  /** (Internal use only) Default constructor. */
662  SystemBase() = default;
663 
664  /** (Internal use only) Adds an already-constructed input port to this System.
665  Insists that the port already contains a reference to this System, and that
666  the port's index is already set to the next available input port index for
667  this System. */
668  // TODO(sherm1) Add check on suitability of `size` parameter for the port's
669  // data type.
670  void AddInputPort(std::unique_ptr<InputPortBase> port) {
671  DRAKE_DEMAND(port != nullptr);
672  DRAKE_DEMAND(&port->get_system_base() == this);
673  DRAKE_DEMAND(port->get_index() == this->get_num_input_ports());
674  input_ports_.push_back(std::move(port));
675  }
676 
677  /** (Internal use only) Adds an already-constructed output port to this
678  System. Insists that the port already contains a reference to this System, and
679  that the port's index is already set to the next available output port index
680  for this System. */
681  // TODO(sherm1) Add check on suitability of `size` parameter for the port's
682  // data type.
683  void AddOutputPort(std::unique_ptr<OutputPortBase> port) {
684  DRAKE_DEMAND(port != nullptr);
685  DRAKE_DEMAND(&port->get_system_base() == this);
686  DRAKE_DEMAND(port->get_index() == this->get_num_output_ports());
687  output_ports_.push_back(std::move(port));
688  }
689 
690  /** (Internal use only) Assigns a ticket to a new discrete variable group
691  with the given `index`.
692  @pre The supplied index must be the next available one; that is, indexes
693  must be assigned sequentially. */
697  discrete_state_tickets_.push_back(
698  {ticket, "discrete state group " + std::to_string(index)});
699  }
700 
701  /** (Internal use only) Assigns a ticket to a new abstract state variable with
702  the given `index`.
703  @pre The supplied index must be the next available one; that is, indexes
704  must be assigned sequentially. */
707  DRAKE_DEMAND(index == num_abstract_states());
708  abstract_state_tickets_.push_back(
709  {ticket, "abstract state " + std::to_string(index)});
710  }
711 
712  /** (Internal use only) Assigns a ticket to a new numeric parameter with
713  the given `index`.
714  @pre The supplied index must be the next available one; that is, indexes
715  must be assigned sequentially. */
719  numeric_parameter_tickets_.push_back(
720  {ticket, "numeric parameter " + std::to_string(index)});
721  }
722 
723  /** (Internal use only) Assigns a ticket to a new abstract parameter with
724  the given `index`.
725  @pre The supplied index must be the next available one; that is, indexes
726  must be assigned sequentially. */
730  abstract_parameter_tickets_.push_back(
731  {ticket, "abstract parameter " + std::to_string(index)});
732  }
733 
734  /** (Internal use only) This is for cache entries associated with pre-defined
735  tickets, for example the cache entry for time derivatives. See the public API
736  for the most-general DeclareCacheEntry() signature for the meanings of the
737  other parameters here. */
739  DependencyTicket known_ticket,
740  std::string description, CacheEntry::AllocCallback alloc_function,
741  CacheEntry::CalcCallback calc_function,
742  std::set<DependencyTicket> prerequisites_of_calc = {
743  all_sources_ticket()});
744 
745  /** Returns a pointer to the service interface of the immediately enclosing
746  Diagram if one has been set, otherwise nullptr. */
747  const internal::SystemParentServiceInterface* get_parent_service() const {
748  return parent_service_;
749  }
750 
751  /** (Internal use only) Assigns the next unused dependency ticket number,
752  unique only within a particular system. Each call to this method increments
753  the ticket number. */
755  return next_available_ticket_++;
756  }
757 
758  /** (Internal use only) Declares that `parent_service` is the service
759  interface of the Diagram that owns this subsystem. Aborts if the parent
760  service has already been set to something else. */
761  // Use static method so Diagram can invoke this on behalf of a child.
762  // Output argument is listed first because it is serving as the 'this'
763  // pointer here.
764  static void set_parent_service(
765  SystemBase* child,
766  const internal::SystemParentServiceInterface* parent_service) {
767  DRAKE_DEMAND(child != nullptr && parent_service != nullptr);
768  DRAKE_DEMAND(child->parent_service_ == nullptr ||
769  child->parent_service_ == parent_service);
770  child->parent_service_ = parent_service;
771  }
772 
773  /** (Internal use only) Shared code for updating an input port and returning a
774  pointer to its abstract value, or nullptr if the port is not connected. `func`
775  should be the user-visible API function name obtained with __func__. */
776  const AbstractValue* EvalAbstractInputImpl(const char* func,
777  const ContextBase& context,
778  InputPortIndex port_index) const;
779 
780  /** Throws std::out_of_range to report a negative `port_index` that was
781  passed to API method `func`. Caller must ensure that the function name
782  makes it clear what kind of port we're complaining about. */
783  // We're taking an int here for the index; InputPortIndex and OutputPortIndex
784  // can't be negative.
785  [[noreturn]] void ThrowNegativePortIndex(const char* func,
786  int port_index) const;
787 
788  /** Throws std::out_of_range to report bad input `port_index` that was passed
789  to API method `func`. */
790  [[noreturn]] void ThrowInputPortIndexOutOfRange(
791  const char* func, InputPortIndex port_index) const;
792 
793  /** Throws std::out_of_range to report bad output `port_index` that was passed
794  to API method `func`. */
795  [[noreturn]] void ThrowOutputPortIndexOutOfRange(
796  const char* func, OutputPortIndex port_index) const;
797 
798  /** Throws std::logic_error because someone misused API method `func`, that is
799  only allowed for declared-vector input ports, on an abstract port whose
800  index is given here. */
801  [[noreturn]] void ThrowNotAVectorInputPort(const char* func,
802  InputPortIndex port_index) const;
803 
804  /** Throws std::logic_error because someone called API method `func` claiming
805  the input port had some value type that was wrong. */
806  [[noreturn]] void ThrowInputPortHasWrongType(
807  const char* func, InputPortIndex port_index,
808  const std::string& expected_type, const std::string& actual_type) const;
809 
810  /** Throws std::logic_error because someone called API method `func`, that
811  requires this input port to be evaluatable, but the port was neither
812  fixed nor connected. */
813  [[noreturn]] void ThrowCantEvaluateInputPort(const char* func,
814  InputPortIndex port_index) const;
815 
816  /** (Internal use only) Returns the InputPortBase at index `port_index`,
817  throwing std::out_of_range we don't like the port index. The name of the
818  public API method that received the bad index is provided in `func` and is
819  included in the error message. */
820  const InputPortBase& GetInputPortBaseOrThrow(const char* func,
821  int port_index) const {
822  if (port_index < 0)
823  ThrowNegativePortIndex(func, port_index);
824  const InputPortIndex port(port_index);
825  if (port_index >= get_num_input_ports())
826  ThrowInputPortIndexOutOfRange(func, port);
827  return *input_ports_[port];
828  }
829 
830  /** (Internal use only) Returns the OutputPortBase at index `port_index`,
831  throwing std::out_of_range we don't like the port index. The name of the
832  public API method that received the bad index is provided in `func` and is
833  included in the error message. */
834  const OutputPortBase& GetOutputPortBaseOrThrow(const char* func,
835  int port_index) const {
836  if (port_index < 0)
837  ThrowNegativePortIndex(func, port_index);
838  const OutputPortIndex port(port_index);
839  if (port_index >= get_num_output_ports())
840  ThrowOutputPortIndexOutOfRange(func, port);
841  return *output_ports_[port_index];
842  }
843 
844  /** This method must be invoked from within derived class DoAllocateContext()
845  implementations right after the concrete Context object has been allocated.
846  It allocates cache entries, sets up all intra-Context dependencies, and marks
847  the ContextBase as initialized so that we can verify proper derived-class
848  behavior.
849  @pre The supplied context must not be null and must not already have been
850  initialized. */
851  void InitializeContextBase(ContextBase* context) const;
852 
853  /** Derived class implementations should allocate a suitable concrete Context
854  type, then invoke the above InitializeContextBase() method. A Diagram must
855  then invoke AllocateContext() to obtain each of the subcontexts for its
856  DiagramContext, and must set up inter-subcontext dependencies among its
857  children and between itself and its children. Then context resources such as
858  parameters and state should be allocated. */
859  virtual std::unique_ptr<ContextBase> DoAllocateContext() const = 0;
860 
861  /** Derived classes must implement this to verify that the supplied
862  Context is suitable, and throw an exception if not. This is a runtime check
863  but may be expensive so is not guaranteed to be invoked except in Debug
864  builds. */
865  virtual void DoCheckValidContext(const ContextBase&) const = 0;
866 
867  private:
868  void CreateSourceTrackers(ContextBase*) const;
869 
870  // Used to create trackers for variable-number System-allocated objects.
871  struct TrackerInfo {
872  DependencyTicket ticket;
873  std::string description;
874  };
875 
876  const TrackerInfo& discrete_state_tracker_info(
877  DiscreteStateIndex index) const {
878  DRAKE_DEMAND(0 <= index && index < num_discrete_state_groups());
879  return discrete_state_tickets_[index];
880  }
881 
882  const TrackerInfo& abstract_state_tracker_info(
883  AbstractStateIndex index) const {
884  DRAKE_DEMAND(0 <= index && index < num_abstract_states());
885  return abstract_state_tickets_[index];
886  }
887 
888  const TrackerInfo& numeric_parameter_tracker_info(
889  NumericParameterIndex index) const {
890  DRAKE_DEMAND(0 <= index && index < num_numeric_parameters());
891  return numeric_parameter_tickets_[index];
892  }
893 
894  const TrackerInfo& abstract_parameter_tracker_info(
895  AbstractParameterIndex index) const {
896  DRAKE_DEMAND(0 <= index && index < num_abstract_parameters());
897  return abstract_parameter_tickets_[index];
898  }
899 
900  // Ports and cache entries hold their own DependencyTickets. Note that the
901  // addresses of the elements are stable even if the std::vectors are resized.
902 
903  // Indexed by InputPortIndex.
904  std::vector<std::unique_ptr<InputPortBase>> input_ports_;
905  // Indexed by OutputPortIndex.
906  std::vector<std::unique_ptr<OutputPortBase>> output_ports_;
907  // Indexed by CacheIndex.
908  std::vector<std::unique_ptr<CacheEntry>> cache_entries_;
909 
910  // States and parameters don't hold their own tickets so we track them here.
911 
912  // Indexed by DiscreteStateIndex.
913  std::vector<TrackerInfo> discrete_state_tickets_;
914  // Indexed by AbstractStateIndex.
915  std::vector<TrackerInfo> abstract_state_tickets_;
916  // Indexed by NumericParameterIndex.
917  std::vector<TrackerInfo> numeric_parameter_tickets_;
918  // Indexed by AbstractParameterIndex.
919  std::vector<TrackerInfo> abstract_parameter_tickets_;
920 
921  // Initialize to the first ticket number available after all the well-known
922  // ones. This gets incremented as tickets are handed out for the optional
923  // entities above.
924  DependencyTicket next_available_ticket_{internal::kNextAvailableTicket};
925 
926  // The enclosing Diagram. Null/invalid when this is the root system.
927  const internal::SystemParentServiceInterface* parent_service_{nullptr};
928 
929  // Name of this system.
930  std::string name_;
931 };
932 
933 // Implementations of templatized DeclareCacheEntry() methods.
934 
935 // Takes make() and calc() member functions.
936 template <class MySystem, class MyContext, typename ValueType>
938  std::string description,
939  ValueType (MySystem::*make)() const,
940  void (MySystem::*calc)(const MyContext&, ValueType*) const,
941  std::set<DependencyTicket> prerequisites_of_calc) {
943  "Expected to be invoked from a SystemBase-derived System.");
945  "Expected to be invoked with a ContextBase-derived Context.");
946  auto this_ptr = dynamic_cast<const MySystem*>(this);
947  DRAKE_DEMAND(this_ptr != nullptr);
948  auto alloc_callback = [this_ptr, make]() {
949  return AbstractValue::Make((this_ptr->*make)());
950  };
951  auto calc_callback = [this_ptr, calc](const ContextBase& context,
953  const auto& typed_context = dynamic_cast<const MyContext&>(context);
954  ValueType& typed_result = result->GetMutableValue<ValueType>();
955  (this_ptr->*calc)(typed_context, &typed_result);
956  };
957  // Invoke the general signature above.
958  auto& entry = DeclareCacheEntry(
959  std::move(description), std::move(alloc_callback),
960  std::move(calc_callback), std::move(prerequisites_of_calc));
961  return entry;
962 }
963 
964 // Takes an initial value and calc() member function.
965 template <class MySystem, class MyContext, typename ValueType>
967  std::string description, const ValueType& model_value,
968  void (MySystem::*calc)(const MyContext&, ValueType*) const,
969  std::set<DependencyTicket> prerequisites_of_calc) {
971  "Expected to be invoked from a SystemBase-derived System.");
973  "Expected to be invoked with a ContextBase-derived Context.");
974  auto this_ptr = dynamic_cast<const MySystem*>(this);
975  DRAKE_DEMAND(this_ptr != nullptr);
976  // The given model value may have *either* a copy constructor or a Clone()
977  // method, since it just has to be suitable for containing in an
978  // AbstractValue. We need to create a functor that is copy constructible,
979  // so need to wrap the model value to give it a copy constructor. Drake's
980  // copyable_unique_ptr does just that, so is suitable for capture by the
981  // allocator functor here.
983  std::make_unique<Value<ValueType>>(model_value));
984  auto alloc_callback = [model = std::move(owned_model)]() {
985  return model->Clone();
986  };
987  auto calc_callback = [this_ptr, calc](const ContextBase& context,
989  const auto& typed_context = dynamic_cast<const MyContext&>(context);
990  ValueType& typed_result = result->GetMutableValue<ValueType>();
991  (this_ptr->*calc)(typed_context, &typed_result);
992  };
993  auto& entry = DeclareCacheEntry(
994  std::move(description), std::move(alloc_callback),
995  std::move(calc_callback), std::move(prerequisites_of_calc));
996  return entry;
997 }
998 
999 // Takes just a calc() member function, value-initializes entry.
1000 template <class MySystem, class MyContext, typename ValueType>
1002  std::string description,
1003  void (MySystem::*calc)(const MyContext&, ValueType*) const,
1004  std::set<DependencyTicket> prerequisites_of_calc) {
1006  "Expected to be invoked from a SystemBase-derived System.");
1008  "Expected to be invoked with a ContextBase-derived Context.");
1009  static_assert(
1011  "SystemBase::DeclareCacheEntry(calc): the calc-only overload of "
1012  "this method requires that the output type has a default constructor");
1013  // Invokes the above model-value method. Note that value initialization {}
1014  // is required here.
1015  return DeclareCacheEntry(std::move(description), ValueType{}, calc,
1016  std::move(prerequisites_of_calc));
1017 }
1018 
1019 } // namespace systems
1020 } // 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 (may be a vector)...
Definition: system_base.h:648
static DependencyTicket xdhat_ticket()
Returns a ticket for the cache entry that holds the discrete state update for the numerical discrete ...
Definition: system_base.h:526
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:834
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:820
void AddNumericParameter(NumericParameterIndex index)
(Internal use only) Assigns a ticket to a new numeric parameter with the given index.
Definition: system_base.h:716
static DependencyTicket xcdot_ticket()
Returns a ticket for the cache entry that holds time derivatives of the continuous variables...
Definition: system_base.h:520
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:618
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:670
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 the input port indicated by index.
Definition: system_base.h:590
Definition: automotive_demo.cc:90
static DependencyTicket xa_ticket()
Returns a ticket indicating dependence on all of the abstract state variables in the current Context...
Definition: system_base.h:504
static DependencyTicket all_parameters_ticket()
Returns a ticket indicating dependence on all parameters p in this system, including numeric paramete...
Definition: system_base.h:577
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:231
static DependencyTicket all_state_ticket()
Returns a ticket indicating dependence on all state variables x in this system, including continuous ...
Definition: system_base.h:514
DependencyTicket cache_entry_ticket(CacheIndex index)
Returns a ticket indicating dependence on the cache entry indicated by index.
Definition: system_base.h:606
void AddAbstractState(AbstractStateIndex index)
(Internal use only) Assigns a ticket to a new abstract state variable with the given index...
Definition: system_base.h:705
~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:624
void AddAbstractParameter(AbstractParameterIndex index)
(Internal use only) Assigns a ticket to a new abstract parameter with the given index.
Definition: system_base.h:727
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
static DependencyTicket velocity_ticket()
(Advanced) Returns a ticket indicating dependence on all of the velocity variables, but not the configuration variables for this System.
Definition: system_base.h:562
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:415
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:683
DependencyTicket abstract_state_ticket(AbstractStateIndex index) const
Returns a ticket indicating dependence on a particular abstract state variable.
Definition: system_base.h:642
DependencyTicket output_port_ticket(OutputPortIndex index)
Returns a ticket indicating dependence on the output port indicated by index.
Definition: system_base.h:598
std::string to_string(const drake::geometry::Identifier< Tag > &id)
Enables use of identifiers with to_string.
Definition: identifier.h:211
static DependencyTicket all_input_ports_ticket()
Returns a ticket indicating dependence on all input ports u of this system.
Definition: system_base.h:583
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:188
std::vector< Number > result
Definition: ipopt_solver.cc:151
Provides non-templatized functionality shared by the templatized derived classes. ...
Definition: context_base.h:38
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:204
static DependencyTicket xc_ticket()
Returns a ticket indicating dependence on all of the continuous state variables q, v, or z.
Definition: system_base.h:492
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:212
static DependencyTicket accuracy_ticket()
Returns a ticket indicating dependence on the accuracy setting in the Context.
Definition: system_base.h:467
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:196
static DependencyTicket q_ticket()
Returns a ticket indicating that a computation depends on configuration state variables q...
Definition: system_base.h:473
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:764
static DependencyTicket configuration_ticket()
Returns a ticket indicating dependence on all the configuration variables for this System...
Definition: system_base.h:542
void AddDiscreteStateGroup(DiscreteStateIndex index)
(Internal use only) Assigns a ticket to a new discrete variable group with the given index...
Definition: system_base.h:694
static DependencyTicket time_ticket()
Returns a ticket indicating dependence on time.
Definition: system_base.h:460
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:222
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.
Definition: system_base.h:654
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:613
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:754
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:165
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:454
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 all of the miscellaneous continuous state variables z...
Definition: system_base.h:486
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:480
int num_abstract_parameters() const
Returns the number of declared abstract parameters.
Definition: system_base.h:629
static DependencyTicket all_sources_ticket()
Returns a ticket indicating dependence on every possible independent source value, including time, state, input ports, parameters, and the accuracy setting (but not cache entries).
Definition: system_base.h:447
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 (may be a vector)...
Definition: system_base.h:636
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:747
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 of the configuration and velocity state variables of th...
Definition: system_base.h:571
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:498
An InputPort is a System resource that describes the kind of input a System accepts, on a given port.
Definition: input_port_base.h:20
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