Drake
DiscreteValues< T > Class Template Reference

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

#include <drake/systems/framework/discrete_values.h>

Inheritance diagram for DiscreteValues< T >:

Public Member Functions

 DiscreteValues ()
 Constructs an empty discrete values. 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 DiscreteValues that owns a single datum vector. More...
 
virtual ~DiscreteValues ()
 
int num_groups () const
 
const std::vector< BasicVector< T > * > & get_data () const
 
const BasicVector< T > * get_vector (int index) const
 
BasicVector< T > * get_mutable_vector (int index)
 
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.
int size () const
 Returns the number of elements in the only DiscreteValues group. More...
 
T & operator[] (std::size_t idx)
 
const T & operator[] (std::size_t idx) const
 
const BasicVector< T > * get_vector () const
 
BasicVector< T > * get_mutable_vector ()
 

Detailed Description

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

The 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 of vectors xd = [xd0, xd1...]. Requesting a specific 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.

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 discrete values.

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

Constructs a DiscreteValues that does not own the underlying data.

The data must outlive this DiscreteValues.

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

Constructs a DiscreteValues that owns the underlying data.

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

Constructs a DiscreteValues that owns a single datum vector.

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

Here is the caller graph for this function:

BasicVector<T>* get_mutable_vector ( int  index)
inline
const BasicVector<T>* get_vector ( ) const
inline

Here is the caller graph for this function:

const BasicVector<T>* get_vector ( int  index) const
inline
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
const T& operator[] ( std::size_t  idx) const
inline
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: