Drake
context.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <memory>
4 #include <utility>
5 
6 #include "drake/common/drake_optional.h"
7 #include "drake/common/drake_throw.h"
8 #include "drake/systems/framework/context_base.h"
9 #include "drake/systems/framework/input_port_evaluator_interface.h"
10 #include "drake/systems/framework/input_port_value.h"
11 #include "drake/systems/framework/parameters.h"
12 #include "drake/systems/framework/state.h"
13 #include "drake/systems/framework/value.h"
14 
15 namespace drake {
16 namespace systems {
17 
18 /// Contains information about the independent variable including time and
19 /// step number.
20 // TODO(sherm1) Add step information.
21 template <typename T>
22 struct StepInfo {
23  /// The time, in seconds. For typical T implementations based on
24  /// doubles, time resolution will gradually degrade as time increases.
25  // TODO(sherm1): Consider whether this is sufficiently robust.
26  T time_sec{0.0};
27 };
28 
29 /// %Context is an abstract class template that represents all the typed values
30 /// that are used in a System's computations: time, numeric-valued input ports,
31 /// numerical state, and numerical parameters. There are also type-erased
32 /// abstract state variables, abstract-valued input ports, abstract parameters,
33 /// and a double accuracy setting. The framework provides two concrete
34 /// subclasses of %Context: LeafContext (for leaf Systems) and DiagramContext
35 /// (for composite System Diagrams). Users are forbidden to extend
36 /// DiagramContext and are discouraged from subclassing LeafContext.
37 ///
38 /// @tparam T The mathematical type of the context, which must be a valid Eigen
39 /// scalar.
40 template <typename T>
41 class Context : public ContextBase {
42  public:
43  /// @name Does not allow copy, move, or assignment.
44  //@{
45  // Copy constructor is protected for use in implementing Clone().
46  Context(Context&&) = delete;
47  Context& operator=(const Context&) = delete;
48  Context& operator=(Context&&) = delete;
49  //@}
50 
51  /// Returns a deep copy of this Context.
52  // This is just an intentional shadowing of the base class method to return
53  // a more convenient type.
54  std::unique_ptr<Context<T>> Clone() const {
55  std::unique_ptr<ContextBase> clone_base(ContextBase::Clone());
56  DRAKE_DEMAND(dynamic_cast<Context<T>*>(clone_base.get()) != nullptr);
57  return std::unique_ptr<Context<T>>(
58  static_cast<Context<T>*>(clone_base.release()));
59  }
60 
61  ~Context() override = default;
62 
63  // =========================================================================
64  // Accessors and Mutators for Time.
65 
66  /// Returns the current time in seconds.
67  const T& get_time() const { return get_step_info().time_sec; }
68 
69  /// Set the current time in seconds.
70  virtual void set_time(const T& time_sec) {
71  get_mutable_step_info()->time_sec = time_sec;
72  }
73 
74  // =========================================================================
75  // Accessors and Mutators for State.
76 
77  virtual const State<T>& get_state() const = 0;
78  virtual State<T>& get_mutable_state() = 0;
79 
80  /// Returns true if the Context has no state.
81  bool is_stateless() const {
82  const int nxc = get_continuous_state().size();
83  const int nxd = get_num_discrete_state_groups();
84  const int nxa = get_num_abstract_states();
85  return nxc == 0 && nxd == 0 && nxa == 0;
86  }
87 
88  /// Returns true if the Context has continuous state, but no discrete or
89  /// abstract state.
91  const int nxc = get_continuous_state().size();
92  const int nxd = get_num_discrete_state_groups();
93  const int nxa = get_num_abstract_states();
94  return nxc > 0 && nxd == 0 && nxa == 0;
95  }
96 
97  /// Returns true if the Context has discrete state, but no continuous or
98  /// abstract state.
99  bool has_only_discrete_state() const {
100  const int nxc = get_continuous_state().size();
101  const int nxd = get_num_discrete_state_groups();
102  const int nxa = get_num_abstract_states();
103  return nxd > 0 && nxc == 0 && nxa == 0;
104  }
105 
106  /// Returns the total dimension of all of the basic vector states (as if they
107  /// were muxed).
108  /// @throws std::runtime_error if the system contains any abstract state.
109  int get_num_total_states() const {
110  DRAKE_THROW_UNLESS(get_num_abstract_states() == 0);
111  int count = get_continuous_state().size();
112  for (int i = 0; i < get_num_discrete_state_groups(); i++)
113  count += get_discrete_state(i).size();
114  return count;
115  }
116 
117  /// Sets the continuous state to @p xc, deleting whatever was there before.
118  void set_continuous_state(std::unique_ptr<ContinuousState<T>> xc) {
119  get_mutable_state().set_continuous_state(std::move(xc));
120  }
121 
122  /// Returns a mutable reference to the continuous component of the state,
123  /// which may be of size zero.
125  return get_mutable_state().get_mutable_continuous_state();
126  }
127 
128  /// Returns a mutable reference to the continuous state vector, devoid
129  /// of second-order structure. The vector may be of size zero.
131  return get_mutable_continuous_state().get_mutable_vector();
132  }
133 
134  /// Returns a const reference to the continuous component of the state,
135  /// which may be of size zero.
137  return get_state().get_continuous_state();
138  }
139 
140  /// Returns a reference to the continuous state vector, devoid of second-order
141  /// structure. The vector may be of size zero.
143  return get_continuous_state().get_vector();
144  }
145 
146  /// Returns the number of vectors (groups) in the discrete state.
148  return get_state().get_discrete_state().num_groups();
149  }
150 
151  /// Returns a reference to the entire discrete state, which may consist of
152  /// multiple discrete state vectors (groups).
154  return get_state().get_discrete_state();
155  }
156 
157  /// Returns a reference to the _only_ discrete state vector. The vector may be
158  /// of size zero. Fails if there is more than one discrete state group.
160  return get_discrete_state().get_vector();
161  }
162 
163  /// Returns a mutable reference to the discrete component of the state,
164  /// which may be of size zero.
166  return get_mutable_state().get_mutable_discrete_state();
167  }
168 
169  /// Returns a mutable reference to group (vector) @p index of the discrete
170  /// state.
171  /// @pre @p index must identify an existing group.
173  DiscreteValues<T>& xd = get_mutable_discrete_state();
174  return xd.get_mutable_vector(index);
175  }
176 
177  /// Sets the discrete state to @p xd, deleting whatever was there before.
178  void set_discrete_state(std::unique_ptr<DiscreteValues<T>> xd) {
179  get_mutable_state().set_discrete_state(std::move(xd));
180  }
181 
182  /// Returns a const reference to group (vector) @p index of the discrete
183  /// state.
184  /// @pre @p index must identify an existing group.
185  const BasicVector<T>& get_discrete_state(int index) const {
186  const DiscreteValues<T>& xd = get_state().get_discrete_state();
187  return xd.get_vector(index);
188  }
189 
190  /// Returns the number of elements in the abstract state.
192  return get_state().get_abstract_state().size();
193  }
194 
195  /// Returns a const reference to the abstract component of the state, which
196  /// may be of size zero.
198  return get_state().get_abstract_state();
199  }
200 
201  /// Returns a mutable reference to the abstract component of the state,
202  /// which may be of size zero.
204  return get_mutable_state().get_mutable_abstract_state();
205  }
206 
207  /// Returns a mutable reference to element @p index of the abstract state.
208  /// @pre @p index must identify an existing element.
209  template <typename U>
211  AbstractValues& xa = get_mutable_abstract_state();
212  return xa.get_mutable_value(index).GetMutableValue<U>();
213  }
214 
215  /// Sets the abstract state to @p xa, deleting whatever was there before.
216  void set_abstract_state(std::unique_ptr<AbstractValues> xa) {
217  get_mutable_state().set_abstract_state(std::move(xa));
218  }
219 
220  /// Returns a const reference to the abstract component of the
221  /// state at @p index.
222  /// @pre @p index must identify an existing element.
223  template <typename U>
224  const U& get_abstract_state(int index) const {
225  const AbstractValues& xa = get_state().get_abstract_state();
226  return xa.get_value(index).GetValue<U>();
227  }
228 
229  // =========================================================================
230  // Accessors and Mutators for Input.
231 
232  /// Returns the number of input ports.
233  virtual int get_num_input_ports() const = 0;
234 
235  /// Connects the input port at @p index to a FreestandingInputPortValue with
236  /// the given abstract @p value. Aborts if @p index is out of range.
237  /// Returns a reference to the allocated FreestandingInputPortValue. The
238  /// reference will remain valid until this input port's value source is
239  /// replaced or the %Context is destroyed. You may use that reference to
240  /// modify the input port's value using the appropriate
241  /// FreestandingInputPortValue method, which will ensure that invalidation
242  /// notifications are delivered.
244  int index, std::unique_ptr<AbstractValue> value) {
245  auto free_value_ptr =
246  std::make_unique<FreestandingInputPortValue>(std::move(value));
247  FreestandingInputPortValue& free_value = *free_value_ptr;
248  SetInputPortValue(index, std::move(free_value_ptr));
249  return free_value;
250  }
251 
252  /// Connects the input port at @p index to a FreestandingInputPortValue with
253  /// the given vector @p vec. Otherwise same as above method.
255  int index, std::unique_ptr<BasicVector<T>> vec) {
256  return FixInputPort(
257  index, std::make_unique<Value<BasicVector<T>>>(std::move(vec)));
258  }
259 
260  /// Same as above method but starts with an Eigen vector whose contents are
261  /// used to initialize a BasicVector in the FreestandingInputPortValue.
263  int index, const Eigen::Ref<const VectorX<T>>& data) {
264  auto vec = std::make_unique<BasicVector<T>>(data);
265  return FixInputPort(index, std::move(vec));
266  }
267 
268  /// Evaluates and returns the value of the input port identified by
269  /// @p descriptor, using the given @p evaluator, which should be the Diagram
270  /// containing the System that allocated this Context. The evaluation will be
271  /// performed in this Context's parent. It is a recursive operation that may
272  /// invoke long chains of evaluation through all the Systems that are
273  /// prerequisites to the specified port.
274  ///
275  /// Returns nullptr if the port is not connected to a value source. Aborts if
276  /// the port does not exist.
277  ///
278  /// This is a framework implementation detail. User code should not call it.
281  const InputPortDescriptor<T>& descriptor) const {
282  const InputPortValue* port_value =
283  GetInputPortValue(descriptor.get_index());
284  if (port_value == nullptr) return nullptr;
285  if (port_value->requires_evaluation()) {
286  DRAKE_DEMAND(evaluator != nullptr);
287  evaluator->EvaluateSubsystemInputPort(parent_, descriptor);
288  }
289  return port_value;
290  }
291 
292  /// Evaluates and returns the vector value of the input port with the given
293  /// @p descriptor. This is a recursive operation that may invoke long chains
294  /// of evaluation through all the Systems that are prerequisite to the
295  /// specified port.
296  ///
297  /// Returns nullptr if the port is not connected.
298  /// Throws std::bad_cast if the port is not vector-valued.
299  /// Aborts if the port does not exist.
300  ///
301  /// This is a framework implementation detail. User code should not call it;
302  /// consider calling System::EvalVectorInput instead.
305  const InputPortDescriptor<T>& descriptor) const {
306  const InputPortValue* port_value = EvalInputPort(evaluator, descriptor);
307  if (port_value == nullptr) return nullptr;
308  return port_value->template get_vector_data<T>();
309  }
310 
311  /// Evaluates and returns the abstract value of the input port with the given
312  /// @p descriptor. This is a recursive operation that may invoke long chains
313  /// of evaluation through all the Systems that are prerequisite to the
314  /// specified port.
315  ///
316  /// Returns nullptr if the port is not connected.
317  /// Aborts if the port does not exist.
318  ///
319  /// This is a framework implementation detail. User code should not call it;
320  /// consider calling System::EvalAbstractInput instead.
323  const InputPortDescriptor<T>& descriptor) const {
324  const InputPortValue* port_value = EvalInputPort(evaluator, descriptor);
325  if (port_value == nullptr) return nullptr;
326  return port_value->get_abstract_data();
327  }
328 
329  /// Evaluates and returns the data of the input port at @p index.
330  /// This is a recursive operation that may invoke long chains of evaluation
331  /// through all the Systems that are prerequisite to the specified port.
332  ///
333  /// Returns nullptr if the port is not connected.
334  /// Throws std::bad_cast if the port does not have type V.
335  /// Aborts if the port does not exist.
336  ///
337  /// This is a framework implementation detail. User code should not call it;
338  /// consider calling System::EvalInputValue instead.
339  ///
340  /// @tparam V The type of data expected.
341  template <typename V>
342  const V* EvalInputValue(
344  const InputPortDescriptor<T>& descriptor) const {
345  const AbstractValue* value = EvalAbstractInput(evaluator, descriptor);
346  if (value == nullptr) return nullptr;
347  return &(value->GetValue<V>());
348  }
349 
350  // =========================================================================
351  // Accessors and Mutators for Parameters.
352 
353  virtual const Parameters<T>& get_parameters() const = 0;
354  virtual Parameters<T>& get_mutable_parameters() = 0;
355 
356  /// Returns the number of vector-valued parameters.
358  return get_parameters().num_numeric_parameters();
359  }
360 
361  /// Returns a const reference to the vector-valued parameter at @p index.
362  /// Asserts if @p index doesn't exist.
363  const BasicVector<T>& get_numeric_parameter(int index) const {
364  return get_parameters().get_numeric_parameter(index);
365  }
366 
367  /// Returns a mutable reference to element @p index of the vector-valued
368  /// parameters. Asserts if @p index doesn't exist.
370  return get_mutable_parameters().get_mutable_numeric_parameter(index);
371  }
372 
373  /// Returns the number of abstract-valued parameters.
375  return get_parameters().num_abstract_parameters();
376  }
377 
378  /// Returns a const reference to the abstract-valued parameter at @p index.
379  /// Asserts if @p index doesn't exist.
380  const AbstractValue& get_abstract_parameter(int index) const {
381  return get_parameters().get_abstract_parameter(index);
382  }
383 
384  /// Returns a mutable reference to element @p index of the abstract-valued
385  /// parameters. Asserts if @p index doesn't exist.
387  return get_mutable_parameters().get_mutable_abstract_parameter(index);
388  }
389 
390  // =========================================================================
391  // Accessors and Mutators for Accuracy.
392 
393  /// Records the user's requested accuracy. If no accuracy is requested,
394  /// computations are free to choose suitable defaults, or to refuse to
395  /// proceed without an explicit accuracy setting.
396  ///
397  /// Requested accuracy is stored in the %Context for two reasons:
398  /// - It permits all computations performed over a System to see the _same_
399  /// accuracy request since accuracy is stored in one shared place, and
400  /// - it allows us to invalidate accuracy-dependent cached computations when
401  /// the requested accuracy has changed.
402  ///
403  /// The accuracy of a complete simulation or other numerical study depends on
404  /// the accuracy of _all_ contributing computations, so it is important that
405  /// each computation is done in accordance with the overall requested
406  /// accuracy. Some examples of where this is needed:
407  /// - Error-controlled numerical integrators use the accuracy setting to
408  /// decide what step sizes to take.
409  /// - The Simulator employs a numerical integrator, but also uses accuracy to
410  /// decide how precisely to isolate witness function zero crossings.
411  /// - Iterative calculations reported as results or cached internally depend
412  /// on accuracy to decide how strictly to converge the results. Examples of
413  /// these are: constraint projection, calculation of distances between
414  /// smooth shapes, and deformation calculations for soft contact.
415  ///
416  /// The common thread among these examples is that they all share the
417  /// same %Context, so by keeping accuracy here it can be used effectively to
418  /// control all accuracy-dependent computations.
419  // TODO(edrumwri) Invalidate all cached accuracy-dependent computations, and
420  // propagate accuracy to all subcontexts in a diagram context.
421  virtual void set_accuracy(const optional<double>& accuracy) {
422  accuracy_ = accuracy;
423  }
424 
425  /// Returns the accuracy setting (if any).
426  /// @see set_accuracy() for details.
427  const optional<double>& get_accuracy() const { return accuracy_; }
428 
429  // =========================================================================
430  // Miscellaneous Public Methods
431 
432  /// Returns a deep copy of this Context's State.
433  std::unique_ptr<State<T>> CloneState() const {
434  return DoCloneState();
435  }
436 
437  /// Initializes this context's time, state, and parameters from the real
438  /// values in @p source, regardless of this context's scalar type.
439  /// Requires a constructor T(double).
441  set_time(T(source.get_time()));
442  set_accuracy(source.get_accuracy());
443  get_mutable_state().SetFrom(source.get_state());
444  get_mutable_parameters().SetFrom(source.get_parameters());
445  }
446 
447  /// Declares that @p parent is the context of the enclosing Diagram. The
448  /// enclosing Diagram context is needed to evaluate inputs recursively.
449  /// Aborts if the parent has already been set to something else.
450  ///
451  /// This is a dangerous implementation detail. Conceptually, a Context
452  /// ought to be completely ignorant of its parent Context. However, we
453  /// need this pointer so that we can cause our inputs to be evaluated in
454  /// EvalInputPort. See https://github.com/RobotLocomotion/drake/pull/3455.
455  void set_parent(const Context<T>* parent) {
456  DRAKE_DEMAND(parent_ == nullptr || parent_ == parent);
457  parent_ = parent;
458  }
459 
460  /// Throws an exception unless the given @p descriptor matches the inputs
461  /// actually connected to this context in shape.
462  /// Supports any scalar type of `descriptor`, but expects T by default.
463  ///
464  /// @tparam T1 the scalar type of the InputPortDescriptor to check.
465  template<typename T1 = T>
466  void VerifyInputPort(const InputPortDescriptor<T1>& descriptor) const {
467  const int i = descriptor.get_index();
468  const InputPortValue* port_value = GetInputPortValue(i);
469  // If the port isn't connected, we don't have anything else to check.
470  if (port_value == nullptr) { return; }
471  // TODO(david-german-tri, sherm1): Consider checking sampling here.
472 
473  // In the vector-valued case, check the size.
474  if (descriptor.get_data_type() == kVectorValued) {
475  const BasicVector<T>* input_vector =
476  port_value->template get_vector_data<T>();
477  DRAKE_THROW_UNLESS(input_vector != nullptr);
478  DRAKE_THROW_UNLESS(input_vector->size() == descriptor.size());
479  }
480  // In the abstract-valued case, there is nothing else to check.
481  }
482 
483  protected:
484  Context() = default;
485 
486  /// Copy constructor takes care of base class and `Context<T>` data members.
487  /// Derived classes must implement copy constructors that delegate to this
488  /// one for use in their DoCloneWithoutPointers() implementations.
489  // Default implementation invokes the base class copy constructor and then
490  // the local member copy constructors.
491  Context(const Context<T>&) = default;
492 
493  /// Clones a context but without any of its internal pointers.
494  // Structuring this as a static method permits a DiagramContext to invoke
495  // this protected functionality on its children.
496  // This is just an intentional shadowing of the base class method to return a
497  // more convenient type.
498  static std::unique_ptr<Context<T>> CloneWithoutPointers(
499  const Context<T>& source) {
500  std::unique_ptr<ContextBase> clone_base(
502  DRAKE_DEMAND(dynamic_cast<Context<T>*>(clone_base.get()) != nullptr);
503  std::unique_ptr<Context<T>> clone(
504  static_cast<Context<T>*>(clone_base.release()));
505  return clone;
506  }
507 
508  /// Override to return the appropriate concrete State class to be returned
509  /// by CloneState().
510  virtual std::unique_ptr<State<T>> DoCloneState() const = 0;
511 
512  /// Returns a const reference to current time and step information.
513  const StepInfo<T>& get_step_info() const { return step_info_; }
514 
515  /// Provides writable access to time and step information, with the side
516  /// effect of invaliding any computation that is dependent on them.
517  /// TODO(david-german-tri) Invalidate all cached time- and step-dependent
518  /// computations.
519  StepInfo<T>* get_mutable_step_info() { return &step_info_; }
520 
521  /// Returns the InputPortValue at the given @p index, which may be nullptr if
522  /// it has never been set with SetInputPortValue().
523  /// Asserts if @p index is out of range.
524  virtual const InputPortValue* GetInputPortValue(int index) const = 0;
525 
526  /// Allows derived classes to invoke the protected method on subcontexts.
527  static const InputPortValue* GetInputPortValue(const Context<T>& context,
528  int index) {
529  return context.GetInputPortValue(index);
530  }
531 
532  /// Connects the input port at @p index to the value source @p port_value.
533  /// Disconnects whatever value source was previously there, and de-registers
534  /// it from the output port on which it depends. In some Context
535  /// implementations, may require a recursive search through a tree of
536  /// subcontexts. Implementations must abort if @p index is out of range.
537  virtual void SetInputPortValue(
538  int index, std::unique_ptr<InputPortValue> port_value) = 0;
539 
540  /// Allows derived classes to invoke the protected method on subcontexts.
541  static void SetInputPortValue(Context<T>* context, int index,
542  std::unique_ptr<InputPortValue> port_value) {
543  context->SetInputPortValue(index, std::move(port_value));
544  }
545 
546  private:
547  // Current time and step information.
548  StepInfo<T> step_info_;
549 
550  // Accuracy setting.
551  optional<double> accuracy_;
552 
553  // The context of the enclosing Diagram, used in EvalInputPort.
554  // This pointer MUST be treated as a black box. If you call any substantive
555  // methods on it, you are probably making a mistake.
557 };
558 
559 } // namespace systems
560 } // namespace drake
const InputPortValue * EvalInputPort(const detail::InputPortEvaluatorInterface< T > *evaluator, const InputPortDescriptor< T > &descriptor) const
Evaluates and returns the value of the input port identified by descriptor, using the given evaluator...
Definition: context.h:279
void set_parent(const Context< T > *parent)
Declares that parent is the context of the enclosing Diagram.
Definition: context.h:455
AbstractValues is a container for non-numerical state and parameters.
Definition: abstract_values.h:18
static const InputPortValue * GetInputPortValue(const Context< T > &context, int index)
Allows derived classes to invoke the protected method on subcontexts.
Definition: context.h:527
const AbstractValue & get_abstract_parameter(int index) const
Returns a const reference to the abstract-valued parameter at index.
Definition: context.h:380
DiscreteValues< T > & get_mutable_discrete_state()
Returns a mutable reference to the discrete component of the state, which may be of size zero...
Definition: context.h:165
int size() const override
Returns the number of elements in the vector.
Definition: basic_vector.h:62
DiscreteValues is a container for numerical but non-continuous state and parameters.
Definition: discrete_values.h:33
const AbstractValues & get_abstract_state() const
Returns a const reference to the abstract component of the state, which may be of size zero...
Definition: context.h:197
std::unique_ptr< Context< T > > Clone() const
Returns a deep copy of this Context.
Definition: context.h:54
int i
Definition: reset_after_move_test.cc:51
virtual void SetInputPortValue(int index, std::unique_ptr< InputPortValue > port_value)=0
Connects the input port at index to the value source port_value.
const BasicVector< T > & get_numeric_parameter(int index) const
Returns a const reference to the vector-valued parameter at index.
Definition: context.h:363
bool has_only_discrete_state() const
Returns true if the Context has discrete state, but no continuous or abstract state.
Definition: context.h:99
Type wrapper that performs value-initialization on copy construction or assignment.
Definition: reset_on_copy.h:81
virtual const State< T > & get_state() const =0
Definition: automotive_demo.cc:90
const BasicVector< T > & get_discrete_state(int index) const
Returns a const reference to group (vector) index of the discrete state.
Definition: context.h:185
const AbstractValue * EvalAbstractInput(const detail::InputPortEvaluatorInterface< T > *evaluator, const InputPortDescriptor< T > &descriptor) const
Evaluates and returns the abstract value of the input port with the given descriptor.
Definition: context.h:321
void set_discrete_state(std::unique_ptr< DiscreteValues< T >> xd)
Sets the discrete state to xd, deleting whatever was there before.
Definition: context.h:178
int num_abstract_parameters() const
Returns the number of abstract-valued parameters.
Definition: context.h:374
const VectorBase< T > & get_continuous_state_vector() const
Returns a reference to the continuous state vector, devoid of second-order structure.
Definition: context.h:142
Context is an abstract class template that represents all the typed values that are used in a System&#39;...
Definition: context.h:41
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorX
A column vector of any size, templated on scalar type.
Definition: eigen_types.h:46
static std::unique_ptr< ContextBase > CloneWithoutPointers(const ContextBase &source)
Clones a context but without copying any of its internal pointers; the clone&#39;s pointers are set to nu...
Definition: context_base.h:150
void set_continuous_state(std::unique_ptr< ContinuousState< T >> xc)
Sets the continuous state to xc, deleting whatever was there before.
Definition: context.h:118
VectorBase is an abstract base class that real-valued signals between Systems and real-valued System ...
Definition: vector_base.h:27
#define DRAKE_THROW_UNLESS(condition)
Evaluates condition and iff the value is false will throw an exception with a message showing at leas...
Definition: drake_throw.h:23
StepInfo< T > * get_mutable_step_info()
Provides writable access to time and step information, with the side effect of invaliding any computa...
Definition: context.h:519
virtual const Parameters< T > & get_parameters() const =0
InputPortDescriptor is a notation for specifying the kind of input a System accepts, on a given port.
Definition: input_port_descriptor.h:21
static std::unique_ptr< Context< T > > CloneWithoutPointers(const Context< T > &source)
Clones a context but without any of its internal pointers.
Definition: context.h:498
stx::optional< T > optional
Definition: drake_optional.h:22
FreestandingInputPortValue & FixInputPort(int index, std::unique_ptr< AbstractValue > value)
Connects the input port at index to a FreestandingInputPortValue with the given abstract value...
Definition: context.h:243
std::unique_ptr< ContextBase > Clone() const
Creates an identical copy of the concrete context object.
Definition: context_base.cc:11
const T & GetValue() const
Returns the value wrapped in this AbstractValue, which must be of exactly type T. ...
Definition: value.h:134
InputPortIndex get_index() const
Definition: input_port_descriptor.h:70
Provides non-templatized functionality shared by the templatized derived classes. ...
Definition: context_base.h:27
const BasicVector< T > & get_discrete_state_vector() const
Returns a reference to the only discrete state vector.
Definition: context.h:159
U & get_mutable_abstract_state(int index)
Returns a mutable reference to element index of the abstract state.
Definition: context.h:210
T time_sec
The time, in seconds.
Definition: context.h:26
BasicVector< T > & get_mutable_vector()
Returns a mutable reference to the BasicVector containing the values for the only group...
Definition: discrete_values.h:112
const V * EvalInputValue(const detail::InputPortEvaluatorInterface< T > *evaluator, const InputPortDescriptor< T > &descriptor) const
Evaluates and returns the data of the input port at index.
Definition: context.h:342
Definition: framework_common.h:65
void SetTimeStateAndParametersFrom(const Context< double > &source)
Initializes this context&#39;s time, state, and parameters from the real values in source, regardless of this context&#39;s scalar type.
Definition: context.h:440
virtual void set_time(const T &time_sec)
Set the current time in seconds.
Definition: context.h:70
FreestandingInputPortValue & FixInputPort(int index, const Eigen::Ref< const VectorX< T >> &data)
Same as above method but starts with an Eigen vector whose contents are used to initialize a BasicVec...
Definition: context.h:262
int value
Definition: copyable_unique_ptr_test.cc:51
static void SetInputPortValue(Context< T > *context, int index, std::unique_ptr< InputPortValue > port_value)
Allows derived classes to invoke the protected method on subcontexts.
Definition: context.h:541
const U & get_abstract_state(int index) const
Returns a const reference to the abstract component of the state at index.
Definition: context.h:224
InputPortValue identifies the value source for a single System input port.
Definition: input_port_value.h:27
#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
A FreestandingInputPortValue encapsulates a vector or abstract value for use as an internal value sou...
Definition: input_port_value.h:86
int get_num_discrete_state_groups() const
Returns the number of vectors (groups) in the discrete state.
Definition: context.h:147
bool has_only_continuous_state() const
Returns true if the Context has continuous state, but no discrete or abstract state.
Definition: context.h:90
State is a container for all the data comprising the complete state of a particular System at a parti...
Definition: state.h:27
int num_numeric_parameters() const
Returns the number of vector-valued parameters.
Definition: context.h:357
const StepInfo< T > & get_step_info() const
Returns a const reference to current time and step information.
Definition: context.h:513
const T & get_time() const
Returns the current time in seconds.
Definition: context.h:67
virtual void EvaluateSubsystemInputPort(const Context< T > *context, const InputPortDescriptor< T > &id) const =0
Evaluates the input port with the given id in the given context.
const AbstractValue * get_abstract_data() const
Returns the data on this port, which must be connected to a value source.
Definition: input_port_value.h:37
VectorBase< T > & get_mutable_continuous_state_vector()
Returns a mutable reference to the continuous state vector, devoid of second-order structure...
Definition: context.h:130
BasicVector is a semantics-free wrapper around an Eigen vector that satisfies VectorBase.
Definition: basic_vector.h:25
AbstractValue & get_mutable_abstract_parameter(int index)
Returns a mutable reference to element index of the abstract-valued parameters.
Definition: context.h:386
A fully type-erased container class.
Definition: value.h:101
void VerifyInputPort(const InputPortDescriptor< T1 > &descriptor) const
Throws an exception unless the given descriptor matches the inputs actually connected to this context...
Definition: context.h:466
AbstractValues & get_mutable_abstract_state()
Returns a mutable reference to the abstract component of the state, which may be of size zero...
Definition: context.h:203
const AbstractValue & get_value(int index) const
Returns the element of AbstractValues at the given index, or aborts if the index is out-of-bounds...
Definition: abstract_values.cc:33
const BasicVector< T > * EvalVectorInput(const detail::InputPortEvaluatorInterface< T > *evaluator, const InputPortDescriptor< T > &descriptor) const
Evaluates and returns the vector value of the input port with the given descriptor.
Definition: context.h:303
BasicVector< T > & get_mutable_numeric_parameter(int index)
Returns a mutable reference to element index of the vector-valued parameters.
Definition: context.h:369
ContinuousState< T > & get_mutable_continuous_state()
Returns a mutable reference to the continuous component of the state, which may be of size zero...
Definition: context.h:124
Parameters is a container for variables that parameterize a System so that it can represent a family ...
Definition: parameters.h:26
int get_num_total_states() const
Returns the total dimension of all of the basic vector states (as if they were muxed).
Definition: context.h:109
BasicVector< T > & get_mutable_discrete_state(int index)
Returns a mutable reference to group (vector) index of the discrete state.
Definition: context.h:172
const optional< double > & get_accuracy() const
Returns the accuracy setting (if any).
Definition: context.h:427
virtual void set_accuracy(const optional< double > &accuracy)
Records the user&#39;s requested accuracy.
Definition: context.h:421
Contains information about the independent variable including time and step number.
Definition: context.h:22
virtual bool requires_evaluation() const =0
Returns true if this InputPortValue is not in control of its own data.
InputPortEvaluatorInterface is implemented by classes that are able to evaluate the OutputPortValue c...
Definition: input_port_evaluator_interface.h:26
int size() const
Definition: input_port_descriptor.h:72
int get_num_abstract_states() const
Returns the number of elements in the abstract state.
Definition: context.h:191
ContinuousState is a view of, and optionally a container for, all the continuous state variables xc o...
Definition: continuous_state.h:76
const DiscreteValues< T > & get_discrete_state() const
Returns a reference to the entire discrete state, which may consist of multiple discrete state vector...
Definition: context.h:153
A container class for an arbitrary type T.
Definition: value.h:244
AbstractValue & get_mutable_value(int index)
Returns the element of AbstractValues at the given index, or aborts if the index is out-of-bounds...
Definition: abstract_values.cc:39
const BasicVector< T > & get_vector() const
Returns a const reference to the BasicVector containing the values for the only group.
Definition: discrete_values.h:105
virtual const InputPortValue * GetInputPortValue(int index) const =0
Returns the InputPortValue at the given index, which may be nullptr if it has never been set with Set...
const ContinuousState< T > & get_continuous_state() const
Returns a const reference to the continuous component of the state, which may be of size zero...
Definition: context.h:136
std::unique_ptr< State< T > > CloneState() const
Returns a deep copy of this Context&#39;s State.
Definition: context.h:433
bool is_stateless() const
Returns true if the Context has no state.
Definition: context.h:81
FreestandingInputPortValue & FixInputPort(int index, std::unique_ptr< BasicVector< T >> vec)
Connects the input port at index to a FreestandingInputPortValue with the given vector vec...
Definition: context.h:254
PortDataType get_data_type() const
Definition: input_port_descriptor.h:71
void set_abstract_state(std::unique_ptr< AbstractValues > xa)
Sets the abstract state to xa, deleting whatever was there before.
Definition: context.h:216
int data
Definition: value_test.cc:19
T & GetMutableValue()
Returns the value wrapped in this AbstractValue, which must be of exactly type T. ...
Definition: value.h:163