-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
system_output.h
111 lines (88 loc) · 4 KB
/
system_output.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
#pragma once
#include <memory>
#include <utility>
#include <vector>
#include "drake/common/default_scalars.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/value.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/framework_common.h"
namespace drake {
namespace systems {
// Forward declare for friendship below. Only System<T> may ever create
// a SystemOutput<T>.
template <typename T> class System;
/** Conveniently stores a snapshot of the values of every output port of
a System. There is framework support for allocating the right types and filling
them in but otherwise this is not used internally. Note that there is never any
live connection between a SystemOutput object and the System whose output values
it has captured.
A `SystemOutput<T>` object can only be obtained using
`System<T>::AllocateOutput()` or by copying an existing %SystemOutput object.
@tparam_default_scalar
*/
template <typename T>
class SystemOutput {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(SystemOutput);
~SystemOutput() = default;
/** Returns the number of output ports specified for this %SystemOutput
during allocation. */
int num_ports() const { return static_cast<int>(port_values_.size()); }
// TODO(sherm1) All of these should return references. We don't need to
// support missing entries.
/** Returns the last-saved value of output port `index` as an AbstractValue.
This works for any output port regardless of it actual type. */
const AbstractValue* get_data(int index) const {
DRAKE_ASSERT(0 <= index && index < num_ports());
return port_values_[index].get();
}
/** Returns the last-saved value of output port `index` as a `BasicVector<T>`,
although the actual concrete type is preserved from the actual output port.
@throws std::exception if the port is not vector-valued. */
const BasicVector<T>* get_vector_data(int index) const {
DRAKE_ASSERT(0 <= index && index < num_ports());
return &port_values_[index]->template get_value<BasicVector<T>>();
}
/** (Advanced) Returns mutable access to an AbstractValue object that is
suitable for holding the value of output port `index` of the allocating
System. This works for any output port regardless of it actual type. Most
users should just call `System<T>::CalcOutputs()` to get all the output
port values at once. */
AbstractValue* GetMutableData(int index) {
DRAKE_ASSERT(0 <= index && index < num_ports());
return port_values_[index].get_mutable();
}
/** (Advanced) Returns mutable access to a `BasicVector<T>` object that is
suitable for holding the value of output port `index` of the allocating
System. The object's concrete type is preserved from the output port. Most
users should just call `System<T>::CalcOutputs()` to get all the output
port values at once.
@throws std::exception if the port is not vector-valued. */
BasicVector<T>* GetMutableVectorData(int index) {
DRAKE_ASSERT(0 <= index && index < num_ports());
return &port_values_[index]->template get_mutable_value<BasicVector<T>>();
}
/** (Internal) Gets the id of the System that created this output.
See @ref system_compatibility. */
internal::SystemId get_system_id() const { return system_id_; }
private:
friend class System<T>;
friend class SystemOutputTest;
SystemOutput() = default;
// Add a suitable object to hold values for the next output port.
void add_port(std::unique_ptr<AbstractValue> model_value) {
port_values_.emplace_back(std::move(model_value));
}
// Records the id of the subsystem that created this output.
// See @ref system_compatibility.
void set_system_id(internal::SystemId id) { system_id_ = id; }
std::vector<copyable_unique_ptr<AbstractValue>> port_values_;
// Unique id of the subsystem that created this output.
internal::SystemId system_id_;
};
} // namespace systems
} // namespace drake
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class ::drake::systems::SystemOutput)