maliput
DiscreteValues< T > Class Template Reference

Detailed Description

template<typename T>
class maliput::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.

@tparam_default_scalar

#include <src/maliput/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
 
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 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...
 
void set_value (const Eigen::Ref< const VectorX< T >> &value)
 Sets the vector to the given value for the only group. More...
 
Eigen::VectorBlock< const VectorX< T > > get_value () const
 Returns the entire vector as a const Eigen::VectorBlock 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 (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...
 
Eigen::VectorBlock< const VectorX< T > > get_value (int index) const
 Returns the entire vector as a const Eigen::VectorBlock 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...
 
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...
 

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

Constructor & Destructor Documentation

◆ DiscreteValues() [1/4]

Constructs an empty DiscreteValues object containing no groups.

◆ DiscreteValues() [2/4]

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

Constructs a DiscreteValues that does not own the underlying data.

The referenced data must outlive this DiscreteValues. Every entry must be non-null. @exclude_from_pydrake_mkdoc{This overload is not bound in pydrake.}

◆ DiscreteValues() [3/4]

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

Constructs a DiscreteValues that owns the underlying data.

Every entry must be non-null.

◆ DiscreteValues() [4/4]

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

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

◆ ~DiscreteValues()

virtual ~DiscreteValues ( )
virtual

Member Function Documentation

◆ AppendGroup()

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.

◆ Clone()

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.

◆ get_data()

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

◆ get_mutable_value() [1/2]

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.

◆ get_mutable_value() [2/2]

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.

◆ get_mutable_vector() [1/2]

BasicVector<T>& get_mutable_vector ( )

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

◆ get_mutable_vector() [2/2]

BasicVector<T>& get_mutable_vector ( int  index)

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

◆ get_system_id()

internal::SystemId get_system_id ( ) const

(Internal use only) Gets the id of the subsystem that created this object.

◆ get_value() [1/2]

Eigen::VectorBlock<const VectorX<T> > get_value ( ) const

Returns the entire vector as a const Eigen::VectorBlock for the only group.

◆ get_value() [2/2]

Eigen::VectorBlock<const VectorX<T> > get_value ( int  index) const

Returns the entire vector as a const Eigen::VectorBlock for the indicated group.

◆ get_vector() [1/2]

const BasicVector<T>& get_vector ( ) const

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

◆ get_vector() [2/2]

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

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

◆ num_groups()

int num_groups ( ) const

◆ operator[]() [1/2]

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

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

◆ operator[]() [2/2]

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

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

◆ set_system_id()

void set_system_id ( internal::SystemId  id)

(Internal use only) Records the id of the subsystem that created this object.

◆ set_value() [1/2]

void set_value ( const Eigen::Ref< const VectorX< T >> &  value)

Sets the vector to the given value for the only group.

◆ set_value() [2/2]

void set_value ( int  index,
const Eigen::Ref< const VectorX< T >> &  value 
)

Sets the vector to the given value for the indicated group.

◆ SetFrom()

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.

◆ size()

int size ( ) const

Returns the number of elements in the only DiscreteValues group.


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