Added full Values interface

release/4.3a0
Alex Cunningham 2012-08-07 18:21:35 +00:00
parent 3838fd5508
commit a025b377ec
1 changed files with 20 additions and 0 deletions

20
gtsam.h
View File

@ -1099,14 +1099,34 @@ virtual class NonlinearFactor {
// gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen
};
#include <gtsam/nonlinear/Values.h>
class Values {
Values();
Values(const gtsam::Values& other);
size_t size() const;
bool empty() const;
void clear();
size_t dim() const;
void print(string s) const;
bool equals(const gtsam::Values& other, double tol) const;
void insert(size_t j, const gtsam::Value& value);
void insert(const gtsam::Values& values);
void update(size_t j, const gtsam::Value& val);
void update(const gtsam::Values& values);
void erase(size_t j);
bool exists(size_t j) const;
gtsam::Value at(size_t j) const;
gtsam::KeyList keys() const;
gtsam::VectorValues zeroVectors(const gtsam::Ordering& ordering) const;
gtsam::Values retract(const gtsam::VectorValues& delta, const gtsam::Ordering& ordering) const;
gtsam::VectorValues localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering) const;
void localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering, gtsam::VectorValues& delta) const;
};
// Actually a FastList<Key>