Drake
DiscreteValues< T > Class Template Reference

DiscreteValues is a container for numerical but non-continuous state and parameters. More...

#include <systems/framework/discrete_values.h>

Inheritance diagram for DiscreteValues< T >:
[legend]

Public Member Functions

 DiscreteValues ()
 Constructs an empty DiscreteValues. 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...
 
virtual ~DiscreteValues ()
 
int num_groups () const
 
const std::vector< BasicVector< T > * > & get_data () const
 
const BasicVector< T > & get_vector (int index) const
 Returns a const reference to the vector holding data for the indicated group. More...
 
BasicVector< T > & get_mutable_vector (int index)
 Returns a mutable reference to the vector holding data for the indicated group. More...
 
void CopyFrom (const DiscreteValues< T > &other)
 Writes the values from other into this DiscreteValues, possibly writing through to unowned data. More...
 
void SetFrom (const DiscreteValues< double > &other)
 Resets the values in this DiscreteValues from the values in other, possibly writing through to unowned data. More...
 
std::unique_ptr< DiscreteValuesClone () const
 Returns a deep copy of all the data in this DiscreteValues. More...
 
Does not allow copy, move, or assignment
 DiscreteValues (const DiscreteValues &)=delete
 
DiscreteValuesoperator= (const DiscreteValues &)=delete
 
 DiscreteValues (DiscreteValues &&)=delete
 
DiscreteValuesoperator= (DiscreteValues &&)=delete
 
Convenience accessors for DiscreteValues with just one group.

These will fail (at least in Debug builds) if there is more than 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 BasicVector< T > & get_vector () const
 Returns a const reference to the BasicVector containing the values for the only group. More...
 
BasicVector< T > & get_mutable_vector ()
 Returns a mutable reference to the BasicVector containing the values for the only group. More...
 

Detailed Description

template<typename T>
class drake::systems::DiscreteValues< T >

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.

Template Parameters
TA mathematical type compatible with Eigen's Scalar.

Constructor & Destructor Documentation

DiscreteValues ( const DiscreteValues< T > &  )
delete
DiscreteValues ( DiscreteValues< T > &&  )
delete
DiscreteValues ( )
inline

Constructs an empty DiscreteValues.

DiscreteValues ( const std::vector< BasicVector< T > * > &  data)
inlineexplicit

Constructs a DiscreteValues that does not own the underlying data.

The referenced data must outlive this DiscreteValues. Every entry must be non-null.

DiscreteValues ( std::vector< std::unique_ptr< BasicVector< T >>> &&  data)
inlineexplicit

Constructs a DiscreteValues that owns the underlying data.

Every entry must be non-null.

DiscreteValues ( std::unique_ptr< BasicVector< T >>  datum)
inlineexplicit

Constructs a one-group DiscreteValues object that owns a single datum vector which may not be null.

virtual ~DiscreteValues ( )
inlinevirtual

Member Function Documentation

std::unique_ptr<DiscreteValues> Clone ( ) const
inline

Returns a deep copy of all the data in this DiscreteValues.

The clone will own its own data. This is true regardless of whether the values being cloned had ownership of its data or not.

void CopyFrom ( const DiscreteValues< T > &  other)
inline

Writes the values from other into this DiscreteValues, possibly writing through to unowned data.

Asserts if the dimensions don't match.

Here is the caller graph for this function:

const std::vector<BasicVector<T>*>& get_data ( ) const
inline
BasicVector<T>& get_mutable_vector ( )
inline

Returns a mutable reference to the BasicVector containing the values for the only group.

Here is the caller graph for this function:

BasicVector<T>& get_mutable_vector ( int  index)
inline

Returns a mutable reference to the vector holding data for the indicated group.

const BasicVector<T>& get_vector ( ) const
inline

Returns a const reference to the BasicVector containing the values for the only group.

Here is the caller graph for this function:

const BasicVector<T>& get_vector ( int  index) const
inline

Returns a const reference to the vector holding data for the indicated group.

int num_groups ( ) const
inline

Here is the caller graph for this function:

DiscreteValues& operator= ( DiscreteValues< T > &&  )
delete
DiscreteValues& operator= ( const DiscreteValues< T > &  )
delete
T& operator[] ( std::size_t  idx)
inline

Returns a mutable reference to an element in the only group.

const T& operator[] ( std::size_t  idx) const
inline

Returns a const reference to an element in the only group.

void SetFrom ( const DiscreteValues< double > &  other)
inline

Resets the values in this DiscreteValues from the values in other, possibly writing through to unowned data.

Asserts if the dimensions don't match.

int size ( ) const
inline

Returns the number of elements in the only DiscreteValues group.

Here is the caller graph for this function:


The documentation for this class was generated from the following file: