DiscreteValues is a container for numerical but non-continuous state and parameters.
It may own its underlying data, for use with leaf Systems, or not, for use with Diagrams.
DiscreteValues is an ordered collection xd of BasicVector "groups" so xd = [xd₀, xd₁...], where each group xdᵢ is a contiguous vector. Requesting a specific group index from this collection is the most granular way to retrieve discrete values from the Context, and thus is the unit of cache invalidation. System authors are encouraged to partition their DiscreteValues such that each cacheable computation within the System may depend on only the elements of DiscreteValues that it needs.
None of the contained vectors (groups) may be null, although any of them may be zero-length.
T | The scalar type, which must be one of the default scalars. |
#include <drake/systems/framework/discrete_values.h>
Public Member Functions | |
DiscreteValues () | |
Constructs an empty DiscreteValues object containing no groups. More... | |
DiscreteValues (const std::vector< BasicVector< T > * > &data) | |
Constructs a DiscreteValues that does not own the underlying data . More... | |
DiscreteValues (std::vector< std::unique_ptr< BasicVector< T >>> &&data) | |
Constructs a DiscreteValues that owns the underlying data . More... | |
DiscreteValues (std::unique_ptr< BasicVector< T >> datum) | |
Constructs a one-group DiscreteValues object that owns a single datum vector which may not be null. More... | |
int | AppendGroup (std::unique_ptr< BasicVector< T >> datum) |
Adds an additional group that owns the given datum , which must be non-null. More... | |
virtual | ~DiscreteValues () |
int | num_groups () const |
const std::vector< BasicVector< T > * > & | get_data () const |
template<typename U > | |
void | SetFrom (const DiscreteValues< U > &other) |
Resets the values in this DiscreteValues from the values in other , possibly writing through to unowned data. More... | |
std::unique_ptr< DiscreteValues< T > > | Clone () const |
Creates a deep copy of this object with the same substructure but with all data owned by the copy. More... | |
Does not allow copy, move, or assignment | |
DiscreteValues (const DiscreteValues &)=delete | |
DiscreteValues & | operator= (const DiscreteValues &)=delete |
DiscreteValues (DiscreteValues &&)=delete | |
DiscreteValues & | operator= (DiscreteValues &&)=delete |
Convenience accessors for DiscreteValues with just one group. | |
These will throw if there is not exactly one group in this DiscreteValues object. | |
int | size () const |
Returns the number of elements in the only DiscreteValues group. More... | |
T & | operator[] (std::size_t idx) |
Returns a mutable reference to an element in the only group. More... | |
const T & | operator[] (std::size_t idx) const |
Returns a const reference to an element in the only group. More... | |
const VectorX< T > & | value () const |
Returns a const reference to the underlying VectorX containing the values for the only group. More... | |
void | set_value (const Eigen::Ref< const VectorX< T >> &value) |
Sets the vector to the given value for the only group. More... | |
Eigen::VectorBlock< VectorX< T > > | get_mutable_value () |
Returns the entire vector for the only group as a mutable Eigen::VectorBlock, which allows mutation of the values, but does not allow resize() to be called on the vector. More... | |
const BasicVector< T > & | get_vector () const |
(Advanced) Returns a const reference to the BasicVector containing the values for the only group. More... | |
BasicVector< T > & | get_mutable_vector () |
(Advanced) Returns a mutable reference to the BasicVector containing the values for the only group. More... | |
Eigen::VectorBlock< const VectorX< T > > | get_value () const |
(Don't use this in new code) Returns the entire vector as a const Eigen::VectorBlock for the only group. More... | |
Accessors for DiscreteValues with multiple groups. | |
If you know there is only one group consider using the alternative signatures that don't take a group index. | |
const VectorX< T > & | value (int index) const |
Returns a const reference to the underlying VectorX containing the values for the indicated group. More... | |
Eigen::VectorBlock< VectorX< T > > | get_mutable_value (int index) |
Returns the entire vector for the indicated group as a mutable Eigen::VectorBlock, which allows mutation of the values, but does not allow resize() to be called on the vector. More... | |
void | set_value (int index, const Eigen::Ref< const VectorX< T >> &value) |
Sets the vector to the given value for the indicated group. More... | |
const BasicVector< T > & | get_vector (int index) const |
(Advanced) Returns a const reference to the BasicVector holding data for the indicated group. More... | |
BasicVector< T > & | get_mutable_vector (int index) |
(Advanced) Returns a mutable reference to the BasicVector holding data for the indicated group. More... | |
Eigen::VectorBlock< const VectorX< T > > | get_value (int index) const |
(Don't use this in new code) Returns the entire vector as a const Eigen::VectorBlock for the indicated group. More... | |
System compatibility | |
See System Compatibility. | |
internal::SystemId | get_system_id () const |
(Internal use only) Gets the id of the subsystem that created this object. More... | |
void | set_system_id (internal::SystemId id) |
(Internal use only) Records the id of the subsystem that created this object. More... | |
|
delete |
|
delete |
DiscreteValues | ( | ) |
Constructs an empty DiscreteValues object containing no groups.
|
explicit |
Constructs a DiscreteValues that does not own the underlying data
.
The referenced data must outlive this DiscreteValues. Every entry must be non-null.
|
explicit |
Constructs a DiscreteValues that owns the underlying data
.
Every entry must be non-null.
|
explicit |
Constructs a one-group DiscreteValues object that owns a single datum
vector which may not be null.
|
virtual |
int AppendGroup | ( | std::unique_ptr< BasicVector< T >> | datum | ) |
Adds an additional group that owns the given datum
, which must be non-null.
Returns the assigned group number, counting up from 0 for the first group.
std::unique_ptr<DiscreteValues<T> > Clone | ( | ) | const |
Creates a deep copy of this object with the same substructure but with all data owned by the copy.
That is, if the original was a DiagramDiscreteValues object that maintains a tree of sub-objects, the clone will not include any references to the original sub-objects and is thus decoupled from the Context containing the original. The concrete type of the BasicVector underlying each leaf DiscreteValue is preserved.
const std::vector<BasicVector<T>*>& get_data | ( | ) | const |
Eigen::VectorBlock<VectorX<T> > get_mutable_value | ( | ) |
Returns the entire vector for the only group as a mutable Eigen::VectorBlock, which allows mutation of the values, but does not allow resize() to be called on the vector.
Returns the entire vector for the indicated group as a mutable Eigen::VectorBlock, which allows mutation of the values, but does not allow resize() to be called on the vector.
BasicVector<T>& get_mutable_vector | ( | ) |
(Advanced) Returns a mutable reference to the BasicVector containing the values for the only group.
Prefer get_mutable_value()
to get the underlying Eigen object.
BasicVector<T>& get_mutable_vector | ( | int | index | ) |
(Advanced) Returns a mutable reference to the BasicVector holding data for the indicated group.
Prefer get_mutable_value()
to get the underlying Eigen object unless you really need the BasicVector wrapping it.
internal::SystemId get_system_id | ( | ) | const |
(Internal use only) Gets the id of the subsystem that created this object.
Eigen::VectorBlock<const VectorX<T> > get_value | ( | ) | const |
(Don't use this in new code) Returns the entire vector as a const Eigen::VectorBlock for the only group.
Prefer value()
which returns direct access to the underlying VectorX rather than wrapping it in a VectorBlock.
(Don't use this in new code) Returns the entire vector as a const Eigen::VectorBlock for the indicated group.
Prefer value()
which returns direct access to the underlying VectorX rather than wrapping it in a VectorBlock.
const BasicVector<T>& get_vector | ( | ) | const |
(Advanced) Returns a const reference to the BasicVector containing the values for the only group.
Prefer value()
to get the underlying VectorX directly unless you really need the BasicVector wrapping it.
const BasicVector<T>& get_vector | ( | int | index | ) | const |
(Advanced) Returns a const reference to the BasicVector holding data for the indicated group.
Prefer value(index)
to get the underlying VectorX directly unless you really need the BasicVector wrapping it.
int num_groups | ( | ) | const |
|
delete |
|
delete |
T& operator[] | ( | std::size_t | idx | ) |
Returns a mutable reference to an element in the only group.
const T& operator[] | ( | std::size_t | idx | ) | const |
Returns a const reference to an element in the only group.
void set_system_id | ( | internal::SystemId | id | ) |
(Internal use only) Records the id of the subsystem that created this object.
void set_value | ( | const Eigen::Ref< const VectorX< T >> & | value | ) |
Sets the vector to the given value for the only group.
Sets the vector to the given value for the indicated group.
void SetFrom | ( | const DiscreteValues< U > & | other | ) |
Resets the values in this DiscreteValues from the values in other
, possibly writing through to unowned data.
Throws if the dimensions don't match.
int size | ( | ) | const |
Returns the number of elements in the only DiscreteValues group.
const VectorX<T>& value | ( | ) | const |
Returns a const reference to the underlying VectorX containing the values for the only group.
This is the preferred method for examining the value of the only group.
Returns a const reference to the underlying VectorX containing the values for the indicated group.
This is the preferred method for examining the value of a group.