Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Friends | List of all members
gtsam::Values Class Reference

#include <Values.h>

Inheritance diagram for gtsam::Values:
Inheritance graph
[legend]

Classes

class  ConstFiltered
 
struct  ConstKeyValuePair
 A key-value pair, which you get by dereferencing iterators. More...
 
class  Filtered
 
struct  KeyValuePair
 A key-value pair, which you get by dereferencing iterators. More...
 

Public Types

typedef boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_iterator > const_iterator
 Const forward iterator, with value type ConstKeyValuePair. More...
 
typedef boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_reverse_iterator > const_reverse_iterator
 Const reverse iterator, with value type ConstKeyValuePair. More...
 
typedef boost::shared_ptr< const Valuesconst_shared_ptr
 A const shared_ptr to this class. More...
 
typedef boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::iterator > iterator
 Mutable forward iterator, with value type KeyValuePair. More...
 
typedef boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::reverse_iterator > reverse_iterator
 Mutable reverse iterator, with value type KeyValuePair. More...
 
typedef boost::shared_ptr< Valuesshared_ptr
 A shared_ptr to this class. More...
 
typedef KeyValuePair value_type
 

Public Member Functions

template<typename ValueType >
const ValueType at (Key j) const
 
const Valueat (Key j) const
 
double atDouble (size_t key) const
 version for double More...
 
const_iterator begin () const
 
iterator begin ()
 
void clear ()
 
template<class ValueType >
size_t count () const
 
size_t dim () const
 
bool empty () const
 
const_iterator end () const
 
iterator end ()
 
void erase (Key j)
 
bool exists (Key j) const
 
template<typename ValueType >
boost::optional< const ValueType & > exists (Key j) const
 
Filtered< Valuefilter (const boost::function< bool(Key)> &filterFcn)
 
template<class ValueType >
Filtered< ValueType > filter (const boost::function< bool(Key)> &filterFcn=&_truePredicate< Key >)
 
ConstFiltered< Valuefilter (const boost::function< bool(Key)> &filterFcn) const
 
template<class ValueType >
ConstFiltered< ValueType > filter (const boost::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const
 
iterator find (Key j)
 
const_iterator find (Key j) const
 
void insert (Key j, const Value &val)
 
void insert (const Values &values)
 
template<typename ValueType >
void insert (Key j, const ValueType &val)
 
void insertDouble (Key j, double c)
 version for double More...
 
KeyVector keys () const
 
iterator lower_bound (Key j)
 
const_iterator lower_bound (Key j) const
 
Valuesoperator= (const Values &rhs)
 
const_reverse_iterator rbegin () const
 
reverse_iterator rbegin ()
 
const_reverse_iterator rend () const
 
reverse_iterator rend ()
 
size_t size () const
 
void swap (Values &other)
 
std::pair< iterator, bool > tryInsert (Key j, const Value &value)
 
void update (Key j, const Value &val)
 
template<typename T >
void update (Key j, const T &val)
 
void update (const Values &values)
 
template<typename ValueType >
void update (Key j, const ValueType &val)
 
iterator upper_bound (Key j)
 
const_iterator upper_bound (Key j) const
 
 Values ()
 
 Values (const Values &other)
 
 Values (Values &&other)
 
 Values (std::initializer_list< ConstKeyValuePair > init)
 
 Values (const Values &other, const VectorValues &delta)
 
template<class ValueType >
 Values (const Filtered< ValueType > &view)
 
template<class ValueType >
 Values (const ConstFiltered< ValueType > &view)
 
template<class ValueType >
 Values (const Values::Filtered< ValueType > &view)
 
template<class ValueType >
 Values (const Values::ConstFiltered< ValueType > &view)
 
VectorValues zeroVectors () const
 
Testable
void print (const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 
bool equals (const Values &other, double tol=1e-9) const
 
Manifold Operations
Values retract (const VectorValues &delta) const
 
VectorValues localCoordinates (const Values &cp) const
 

Private Types

typedef KeyValueMap::const_iterator::value_type ConstKeyValuePtrPair
 
typedef boost::ptr_map< Key, Value, std::less< Key >, ValueCloneAllocator, boost::fast_pool_allocator< std::pair< const Key, void * > > > KeyValueMap
 
typedef KeyValueMap::iterator::value_type KeyValuePtrPair
 

Private Member Functions

template<>
bool filterHelper (const boost::function< bool(Key)> filter, const ConstKeyValuePair &key_value)
 
template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Static Private Member Functions

template<class ValueType >
static bool filterHelper (const boost::function< bool(Key)> filter, const ConstKeyValuePair &key_value)
 
static ConstKeyValuePair make_const_deref_pair (const KeyValueMap::const_iterator::value_type &key_value)
 
static KeyValuePair make_deref_pair (const KeyValueMap::iterator::value_type &key_value)
 

Private Attributes

KeyValueMap values_
 

Friends

class boost::serialization::access
 

Detailed Description

A non-templated config holding any types of Manifold-group elements. A values structure is a map from keys to values. It is used to specify the value of a bunch of variables in a factor graph. A Values is a values structure which can hold variables that are elements on manifolds, not just vectors. It then, as a whole, implements a aggregate type which is also a manifold element, and hence supports operations dim, retract, and localCoordinates.

Definition at line 71 of file Values.h.

Member Typedef Documentation

typedef boost::transform_iterator< boost::function1<ConstKeyValuePair, const ConstKeyValuePtrPair&>, KeyValueMap::const_iterator> gtsam::Values::const_iterator

Const forward iterator, with value type ConstKeyValuePair.

Definition at line 124 of file Values.h.

typedef boost::transform_iterator< boost::function1<ConstKeyValuePair, const ConstKeyValuePtrPair&>, KeyValueMap::const_reverse_iterator> gtsam::Values::const_reverse_iterator

Const reverse iterator, with value type ConstKeyValuePair.

Definition at line 132 of file Values.h.

typedef boost::shared_ptr<const Values> gtsam::Values::const_shared_ptr

A const shared_ptr to this class.

Definition at line 99 of file Values.h.

typedef KeyValueMap::const_iterator::value_type gtsam::Values::ConstKeyValuePtrPair
private

Definition at line 90 of file Values.h.

typedef boost::transform_iterator< boost::function1<KeyValuePair, const KeyValuePtrPair&>, KeyValueMap::iterator> gtsam::Values::iterator

Mutable forward iterator, with value type KeyValuePair.

Definition at line 120 of file Values.h.

typedef boost::ptr_map< Key, Value, std::less<Key>, ValueCloneAllocator, boost::fast_pool_allocator<std::pair<const Key, void*> > > gtsam::Values::KeyValueMap
private

Definition at line 84 of file Values.h.

typedef KeyValueMap::iterator::value_type gtsam::Values::KeyValuePtrPair
private

Definition at line 91 of file Values.h.

typedef boost::transform_iterator< boost::function1<KeyValuePair, const KeyValuePtrPair&>, KeyValueMap::reverse_iterator> gtsam::Values::reverse_iterator

Mutable reverse iterator, with value type KeyValuePair.

Definition at line 128 of file Values.h.

typedef boost::shared_ptr<Values> gtsam::Values::shared_ptr

A shared_ptr to this class.

Definition at line 96 of file Values.h.

typedef KeyValuePair gtsam::Values::value_type

Definition at line 134 of file Values.h.

Constructor & Destructor Documentation

gtsam::Values::Values ( )
inline

Default constructor creates an empty Values class

Definition at line 145 of file Values.h.

gtsam::Values::Values ( const Values other)

Copy constructor duplicates all keys and values

Definition at line 47 of file Values.cpp.

gtsam::Values::Values ( Values &&  other)

Move constructor

Definition at line 52 of file Values.cpp.

gtsam::Values::Values ( std::initializer_list< ConstKeyValuePair init)

Constructor from initializer list. Example usage:

Definition at line 56 of file Values.cpp.

gtsam::Values::Values ( const Values other,
const VectorValues delta 
)

Construct from a Values and an update vector: identical to other.retract(delta)

Definition at line 62 of file Values.cpp.

template<class ValueType >
gtsam::Values::Values ( const Filtered< ValueType > &  view)

Constructor from a Filtered view copies out all values

template<class ValueType >
gtsam::Values::Values ( const ConstFiltered< ValueType > &  view)

Constructor from a Filtered or ConstFiltered view

template<class ValueType >
gtsam::Values::Values ( const Values::Filtered< ValueType > &  view)

Constructor from a Filtered view copies out all values

Definition at line 219 of file Values-inl.h.

template<class ValueType >
gtsam::Values::Values ( const Values::ConstFiltered< ValueType > &  view)

Definition at line 228 of file Values-inl.h.

Member Function Documentation

template<typename ValueType >
const ValueType gtsam::Values::at ( Key  j) const

Retrieve a variable by key j. The type of the value associated with this key is supplied as a template argument to this function.

Parameters
jRetrieve the value associated with this key
Template Parameters
ValueTypeThe type of the value stored with this key, this method Throws DynamicValuesIncorrectType if this requested type is not correct. Dynamic matrices/vectors can be retrieved as fixed-size, but not vice-versa.
Returns
The stored value

Definition at line 342 of file Values-inl.h.

const Value & gtsam::Values::at ( Key  j) const

Retrieve a variable by key j. This version returns a reference to the base Value class, and needs to be casted before use.

Parameters
jRetrieve the value associated with this key
Returns
A const reference to the stored value

Definition at line 129 of file Values.cpp.

double gtsam::Values::atDouble ( size_t  key) const
inline

version for double

Definition at line 194 of file Values.h.

const_iterator gtsam::Values::begin ( ) const
inline

Definition at line 241 of file Values.h.

iterator gtsam::Values::begin ( )
inline

Definition at line 243 of file Values.h.

void gtsam::Values::clear ( void  )
inline

Remove all variables from the config

Definition at line 311 of file Values.h.

template<class ValueType >
size_t gtsam::Values::count ( ) const
inline

Definition at line 398 of file Values.h.

size_t gtsam::Values::dim ( ) const

Compute the total dimensionality of all values ( $ O(n) $)

Definition at line 207 of file Values.cpp.

bool gtsam::Values::empty ( ) const
inline

whether the config is empty

Definition at line 239 of file Values.h.

const_iterator gtsam::Values::end ( ) const
inline

Definition at line 242 of file Values.h.

iterator gtsam::Values::end ( )
inline

Definition at line 244 of file Values.h.

bool gtsam::Values::equals ( const Values other,
double  tol = 1e-9 
) const

Test whether the sets of keys and values are identical

Definition at line 88 of file Values.cpp.

void gtsam::Values::erase ( Key  j)

Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present

Definition at line 183 of file Values.cpp.

bool gtsam::Values::exists ( Key  j) const

Check if a value exists with key j. See exists<>(Key j) and exists(const TypedKey& j) for versions that return the value if it exists.

Definition at line 104 of file Values.cpp.

template<typename ValueType >
boost::optional< const ValueType & > gtsam::Values::exists ( Key  j) const

Check if a value with key j exists, returns the value with type Value if the key does exist, or boost::none if it does not exist. Throws DynamicValuesIncorrectType if the value type associated with the requested key does not match the stored value type.

Definition at line 357 of file Values-inl.h.

Values::Filtered< Value > gtsam::Values::filter ( const boost::function< bool(Key)> &  filterFcn)
inline

Return a filtered view of this Values class, without copying any data. When iterating over the filtered view, only the key-value pairs with a key causing filterFcn to return true are visited. Because the object Filtered<Value> returned from filter() is only a view the original Values object must not be deallocated or go out of scope as long as the view is needed.

Parameters
filterFcnThe function that determines which key-value pairs are included in the filtered view, for which this function returns true on their keys.
Returns
A filtered view of the original Values class, which references the original Values class.

Definition at line 237 of file Values-inl.h.

template<class ValueType >
Values::Filtered< ValueType > gtsam::Values::filter ( const boost::function< bool(Key)> &  filterFcn = &_truePredicate<Key>)

Return a filtered view of this Values class, without copying any data. In this templated version, only key-value pairs whose value matches the template argument ValueType and whose key causes the function argument filterFcn to return true are visited when iterating over the filtered view. Because the object Filtered<Value> returned from filter() is only a view the original Values object must not be deallocated or go out of scope as long as the view is needed.

Template Parameters
ValueTypeThe type that the value in a key-value pair must match to be included in the filtered view. Currently, base classes are not resolved so the type must match exactly, except if ValueType = Value, in which case no type filtering is done.
Parameters
filterFcnThe function that determines which key-value pairs are included in the filtered view, for which this function returns true on their keys (default: always return true so that filter() only filters by type, matching ValueType).
Returns
A filtered view of the original Values class, which references the original Values class.

Definition at line 244 of file Values-inl.h.

Values::ConstFiltered< Value > gtsam::Values::filter ( const boost::function< bool(Key)> &  filterFcn) const
inline

Return a filtered view of this Values class, without copying any data. When iterating over the filtered view, only the key-value pairs with a key causing filterFcn to return true are visited. Because the object Filtered<Value> returned from filter() is only a view the original Values object must not be deallocated or go out of scope as long as the view is needed.

Parameters
filterFcnThe function that determines which key-value pairs are included in the filtered view, for which this function returns true on their keys.
Returns
A filtered view of the original Values class, which references the original Values class.

Definition at line 250 of file Values-inl.h.

template<class ValueType >
Values::ConstFiltered< ValueType > gtsam::Values::filter ( const boost::function< bool(Key)> &  filterFcn = &_truePredicate<Key>) const

Return a filtered view of this Values class, without copying any data. In this templated version, only key-value pairs whose value matches the template argument ValueType and whose key causes the function argument filterFcn to return true are visited when iterating over the filtered view. Because the object Filtered<Value> returned from filter() is only a view the original Values object must not be deallocated or go out of scope as long as the view is needed.

Template Parameters
ValueTypeThe type that the value in a key-value pair must match to be included in the filtered view. Currently, base classes are not resolved so the type must match exactly, except if ValueType = Value, in which case no type filtering is done.
Parameters
filterFcnThe function that determines which key-value pairs are included in the filtered view, for which this function returns true on their keys.
Returns
A filtered view of the original Values class, which references the original Values class.

Definition at line 257 of file Values-inl.h.

template<>
bool gtsam::Values::filterHelper ( const boost::function< bool(Key)>  filter,
const ConstKeyValuePair key_value 
)
inlineprivate

Definition at line 263 of file Values-inl.h.

template<class ValueType >
static bool gtsam::Values::filterHelper ( const boost::function< bool(Key)>  filter,
const ConstKeyValuePair key_value 
)
inlinestaticprivate

Definition at line 411 of file Values.h.

iterator gtsam::Values::find ( Key  j)
inline

Find an element by key, returning an iterator, or end() if the key was not found.

Definition at line 217 of file Values.h.

const_iterator gtsam::Values::find ( Key  j) const
inline

Find an element by key, returning an iterator, or end() if the key was not found.

Definition at line 221 of file Values.h.

void gtsam::Values::insert ( Key  j,
const Value val 
)

Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present

Definition at line 140 of file Values.cpp.

void gtsam::Values::insert ( const Values values)

Add a set of variables, throws KeyAlreadyExists<J> if a key is already present

Definition at line 147 of file Values.cpp.

template<typename ValueType >
void gtsam::Values::insert ( Key  j,
const ValueType &  val 
)

Templated version to add a variable with the given j, throws KeyAlreadyExists<J> if j is already present

Definition at line 380 of file Values-inl.h.

void gtsam::Values::insertDouble ( Key  j,
double  c 
)
inline

version for double

Definition at line 274 of file Values.h.

KeyVector gtsam::Values::keys ( ) const

Returns a set of keys in the config Note: by construction, the list is ordered

Definition at line 191 of file Values.cpp.

VectorValues gtsam::Values::localCoordinates ( const Values cp) const

Get a delta config about a linearization point c0 (*this)

Definition at line 114 of file Values.cpp.

iterator gtsam::Values::lower_bound ( Key  j)
inline

Find the element greater than or equal to the specified key.

Definition at line 224 of file Values.h.

const_iterator gtsam::Values::lower_bound ( Key  j) const
inline

Find the element greater than or equal to the specified key.

Definition at line 227 of file Values.h.

static ConstKeyValuePair gtsam::Values::make_const_deref_pair ( const KeyValueMap::const_iterator::value_type &  key_value)
inlinestaticprivate

Definition at line 424 of file Values.h.

static KeyValuePair gtsam::Values::make_deref_pair ( const KeyValueMap::iterator::value_type &  key_value)
inlinestaticprivate

Definition at line 427 of file Values.h.

Values & gtsam::Values::operator= ( const Values rhs)

Replace all keys and variables

Definition at line 200 of file Values.cpp.

void gtsam::Values::print ( const std::string &  str = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const

print method for testing and debugging

Definition at line 77 of file Values.cpp.

const_reverse_iterator gtsam::Values::rbegin ( ) const
inline

Definition at line 245 of file Values.h.

reverse_iterator gtsam::Values::rbegin ( )
inline

Definition at line 247 of file Values.h.

const_reverse_iterator gtsam::Values::rend ( ) const
inline

Definition at line 246 of file Values.h.

reverse_iterator gtsam::Values::rend ( )
inline

Definition at line 248 of file Values.h.

Values gtsam::Values::retract ( const VectorValues delta) const

Add a delta config to current config and returns a new config

Definition at line 109 of file Values.cpp.

template<class ARCHIVE >
void gtsam::Values::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 420 of file Values.h.

size_t gtsam::Values::size ( ) const
inline

The number of variables in this config

Definition at line 236 of file Values.h.

void gtsam::Values::swap ( Values other)
inline

Swap the contents of two Values without copying data

Definition at line 308 of file Values.h.

std::pair< Values::iterator, bool > gtsam::Values::tryInsert ( Key  j,
const Value value 
)

insert that mimics the STL map insert - if the value already exists, the map is not modified and an iterator to the existing value is returned, along with 'false'. If the value did not exist, it is inserted and an iterator pointing to the new element, along with 'true', is returned.

Definition at line 155 of file Values.cpp.

void gtsam::Values::update ( Key  j,
const Value val 
)

single element change of existing element

Definition at line 161 of file Values.cpp.

template<typename T >
void gtsam::Values::update ( Key  j,
const T val 
)

Templated version to update a variable with the given j, throws KeyDoesNotExist<J> if j is not present. If no chart is specified, the DefaultChart<ValueType> is used.

void gtsam::Values::update ( const Values values)

update the current available values without adding new ones

Definition at line 176 of file Values.cpp.

template<typename ValueType >
void gtsam::Values::update ( Key  j,
const ValueType &  val 
)

Definition at line 386 of file Values-inl.h.

iterator gtsam::Values::upper_bound ( Key  j)
inline

Find the lowest-ordered element greater than the specified key.

Definition at line 230 of file Values.h.

const_iterator gtsam::Values::upper_bound ( Key  j) const
inline

Find the lowest-ordered element greater than the specified key.

Definition at line 233 of file Values.h.

VectorValues gtsam::Values::zeroVectors ( ) const

Return a VectorValues of zero vectors for each variable in this Values

Definition at line 216 of file Values.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 418 of file Values.h.

Member Data Documentation

KeyValueMap gtsam::Values::values_
private

Definition at line 87 of file Values.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:37