#include <Values.h>
Classes | |
struct | ConstKeyValuePair |
A key-value pair, which you get by dereferencing iterators. More... | |
struct | deref_iterator |
struct | KeyValuePair |
A key-value pair, which you get by dereferencing iterators. More... | |
Public Types | |
typedef std::shared_ptr< const Values > | const_shared_ptr |
A const shared_ptr to this class. More... | |
typedef std::shared_ptr< Values > | shared_ptr |
A shared_ptr to this class. More... | |
typedef KeyValuePair | value_type |
Public Member Functions | |
void | clear () |
template<class ValueType > | |
size_t | count () const |
size_t | dim () const |
std::map< Key, size_t > | dims () const |
void | erase (Key j) |
template<class ValueType > | |
std::map< Key, ValueType > | extract (const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const |
void | insert (const Values &values) |
template<typename BinaryOp , typename ValueType1 , typename ValueType2 > | |
void | insert (Key j, const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > &val) |
template<typename UnaryOp , typename ValueType > | |
void | insert (Key j, const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > &val) |
void | insert (Key j, const Value &val) |
template<typename ValueType > | |
void | insert (Key j, const ValueType &val) |
void | insert_or_assign (const Values &values) |
template<typename BinaryOp , typename ValueType1 , typename ValueType2 > | |
void | insert_or_assign (Key j, const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > &val) |
template<typename UnaryOp , typename ValueType > | |
void | insert_or_assign (Key j, const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > &val) |
void | insert_or_assign (Key j, const Value &val) |
If key j exists, update value, else perform an insert. More... | |
template<typename ValueType > | |
void | insert_or_assign (Key j, const ValueType &val) |
Templated version to insert_or_assign a variable with the given j. More... | |
void | insertDouble (Key j, double c) |
version for double More... | |
KeyVector | keys () const |
KeySet | keySet () const |
Values & | operator= (const Values &rhs) |
void | swap (Values &other) |
void | update (const Values &values) |
template<typename BinaryOp , typename ValueType1 , typename ValueType2 > | |
void | update (Key j, const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > &val) |
template<typename UnaryOp , typename ValueType > | |
void | update (Key j, const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > &val) |
template<typename T > | |
void | update (Key j, const T &val) |
void | update (Key j, const Value &val) |
template<typename ValueType > | |
void | update (Key j, const ValueType &val) |
VectorValues | zeroVectors () const |
Constructors | |
Values ()=default | |
Values (const Values &other) | |
Values (Values &&other) | |
Values (std::initializer_list< ConstKeyValuePair > init) | |
Values (const Values &other, const VectorValues &delta) | |
Testable | |
void | print (const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
bool | equals (const Values &other, double tol=1e-9) const |
Standard Interface | |
template<typename ValueType > | |
const ValueType | at (Key j) const |
double | atDouble (size_t key) const |
version for double More... | |
const Value & | at (Key j) const |
bool | exists (Key j) const |
template<typename ValueType > | |
const ValueType * | exists (Key j) const |
size_t | size () const |
bool | empty () const |
Iterator | |
deref_iterator | begin () const |
deref_iterator | end () const |
deref_iterator | find (Key j) const |
deref_iterator | lower_bound (Key j) const |
deref_iterator | upper_bound (Key j) const |
Manifold Operations | |
Values | retract (const VectorValues &delta) const |
void | retractMasked (const VectorValues &delta, const KeySet &mask) |
VectorValues | localCoordinates (const Values &cp) const |
Private Types | |
using | KeyValueMap = std::map< Key, std::unique_ptr< Value >, std::less< Key >, std::allocator< std::pair< const Key, std::unique_ptr< Value > >> > |
typedef internal::FastDefaultAllocator< typename std::pair< const Key, void * > >::type | KeyValuePtrPairAllocator |
Static Private Member Functions | |
template<> | |
bool | filterHelper (const std::function< bool(Key)> filter, const ConstKeyValuePair &key_value) |
template<class ValueType > | |
static bool | filterHelper (const std::function< bool(Key)> filter, const ConstKeyValuePair &key_value) |
Private Attributes | |
KeyValueMap | values_ |
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.
typedef std::shared_ptr<const Values> gtsam::Values::const_shared_ptr |
|
private |
typedef std::shared_ptr<Values> gtsam::Values::shared_ptr |
typedef KeyValuePair gtsam::Values::value_type |
|
default |
Default constructor creates an empty Values class
Values::Values | ( | const Values & | other | ) |
Copy constructor duplicates all keys and values
Definition at line 37 of file Values.cpp.
Values::Values | ( | Values && | other | ) |
Move constructor
Definition at line 42 of file Values.cpp.
Values::Values | ( | std::initializer_list< ConstKeyValuePair > | init | ) |
Values::Values | ( | const Values & | other, |
const VectorValues & | delta | ||
) |
Construct from a Values and an update vector: identical to other.retract(delta)
Definition at line 52 of file Values.cpp.
const ValueType 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.
j | Retrieve the value associated with this key |
ValueType | The 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. |
Definition at line 261 of file Values-inl.h.
Retrieve a variable by key j
. This version returns a reference to the base Value class, and needs to be casted before use.
j | Retrieve the value associated with this key |
Definition at line 145 of file Values.cpp.
|
inline |
|
inline |
|
inline |
size_t Values::count |
Definition at line 94 of file Values-inl.h.
size_t Values::dim | ( | ) | const |
Compute the total dimensionality of all values ( )
Definition at line 242 of file Values.cpp.
Return all dimensions in a map ( )
Definition at line 251 of file Values.cpp.
|
inline |
|
inline |
Test whether the sets of keys and values are identical
Definition at line 77 of file Values.cpp.
void Values::erase | ( | Key | j | ) |
Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present
Definition at line 210 of file Values.cpp.
bool 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 93 of file Values.cpp.
const ValueType * Values::exists | ( | Key | j | ) | const |
Check if a value with key j
exists, returns a pointer to the const version of the value Value
if the key does exist, or nullptr 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 276 of file Values-inl.h.
std::map< Key, ValueType > Values::extract | ( | const std::function< bool(Key)> & | filterFcn = &_truePredicate<Key> | ) | const |
Extract a subset of values of the given type ValueType
.
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. This replaces the fancier but very boost-dependent filter
methods that were previously available up to GTSAM 4.2.
ValueType | The 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. |
filterFcn | The 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 ). |
Definition at line 105 of file Values-inl.h.
|
inlinestaticprivate |
Definition at line 121 of file Values-inl.h.
|
inlinestaticprivate |
|
inline |
void Values::insert | ( | const Values & | values | ) |
Add a set of variables, throws KeyAlreadyExists<J> if a key is already present
Definition at line 162 of file Values.cpp.
void Values::insert | ( | Key | j, |
const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > & | val | ||
) |
Partial specialization that allows passing a binary Eigen expression for val.
A binary expression is an expression such as a + b, where a and b are valid Vector or Matrix types of compatible size. The typical usage is for types Point2 (i.e. Eigen::Vector2d) or Point3 (i.e. Eigen::Vector3d). For example, together with the partial specialization for binary operators, a user may call insert(j, 2*a + M*b - c), where M is an appropriately sized matrix (such as a rotation matrix). Thus, it isn't necessary to explicitly evaluate the Eigen expression, as in insert(j, (2*a + M*b - c).eval()), nor is it necessary to first assign the expression to a separate variable.
Definition at line 311 of file Values-inl.h.
void Values::insert | ( | Key | j, |
const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > & | val | ||
) |
Partial specialization that allows passing a unary Eigen expression for val.
A unary expression is an expression such as 2*a or -a, where a is a valid Vector or Matrix type. The typical usage is for types Point2 (i.e. Eigen::Vector2d) or Point3 (i.e. Eigen::Vector3d). For example, together with the partial specialization for binary operators, a user may call insert(j, 2*a + M*b - c), where M is an appropriately sized matrix (such as a rotation matrix). Thus, it isn't necessary to explicitly evaluate the Eigen expression, as in insert(j, (2*a + M*b - c).eval()), nor is it necessary to first assign the expression to a separate variable.
Definition at line 305 of file Values-inl.h.
Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present
Definition at line 155 of file Values.cpp.
void 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 299 of file Values-inl.h.
void Values::insert_or_assign | ( | const Values & | values | ) |
Update a set of variables. If any variable key does not exist, then perform an insert.
Definition at line 203 of file Values.cpp.
void Values::insert_or_assign | ( | Key | j, |
const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > & | val | ||
) |
Partial specialization that allows passing a binary Eigen expression for val, similar to the partial specialization for insert.
Definition at line 345 of file Values-inl.h.
void Values::insert_or_assign | ( | Key | j, |
const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > & | val | ||
) |
Partial specialization that allows passing a unary Eigen expression for val, similar to the partial specialization for insert.
Definition at line 340 of file Values-inl.h.
If key j exists, update value, else perform an insert.
Definition at line 192 of file Values.cpp.
void Values::insert_or_assign | ( | Key | j, |
const ValueType & | val | ||
) |
Templated version to insert_or_assign a variable with the given j.
Definition at line 335 of file Values-inl.h.
|
inline |
KeyVector Values::keys | ( | ) | const |
Returns a vector of keys in the config. Note: by construction, the list is ordered
Definition at line 218 of file Values.cpp.
KeySet Values::keySet | ( | ) | const |
Returns a set of keys in the config.
Definition at line 227 of file Values.cpp.
VectorValues Values::localCoordinates | ( | const Values & | cp | ) | const |
Get a delta config about a linearization point c0 (*this)
Definition at line 129 of file Values.cpp.
|
inline |
Replace all keys and variables
Definition at line 235 of file Values.cpp.
void Values::print | ( | const std::string & | str = "" , |
const KeyFormatter & | keyFormatter = DefaultKeyFormatter |
||
) | const |
print method for testing and debugging
Definition at line 66 of file Values.cpp.
Values Values::retract | ( | const VectorValues & | delta | ) | const |
Add a delta config to current config and returns a new config
Definition at line 98 of file Values.cpp.
void Values::retractMasked | ( | const VectorValues & | delta, |
const KeySet & | mask | ||
) |
Retract, but only for Keys appearing in mask
. In-place.
mask | Mask on Keys where to apply retract. |
Definition at line 103 of file Values.cpp.
|
inline |
|
inline |
void Values::update | ( | const Values & | values | ) |
update the current available values without adding new ones
Definition at line 185 of file Values.cpp.
void Values::update | ( | Key | j, |
const Eigen::CwiseBinaryOp< BinaryOp, const ValueType1, const ValueType2 > & | val | ||
) |
Partial specialization that allows passing a binary Eigen expression for val, similar to the partial specialization for insert.
Definition at line 329 of file Values-inl.h.
void Values::update | ( | Key | j, |
const Eigen::CwiseUnaryOp< UnaryOp, const ValueType > & | val | ||
) |
Partial specialization that allows passing a unary Eigen expression for val, similar to the partial specialization for insert.
Definition at line 323 of file Values-inl.h.
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.
single element change of existing element
Definition at line 169 of file Values.cpp.
void gtsam::Values::update | ( | Key | j, |
const ValueType & | val | ||
) |
Definition at line 317 of file Values-inl.h.
|
inline |
VectorValues Values::zeroVectors | ( | ) | const |
Return a VectorValues of zero vectors for each variable in this Values
Definition at line 260 of file Values.cpp.
|
private |