Added Mike's desired code snippet

release/4.3a0
dellaert 2014-11-10 16:44:48 +01:00
parent 06eb801526
commit fde3805aab
1 changed files with 12 additions and 11 deletions

23
gtsam.h
View File

@ -1670,17 +1670,6 @@ class Values {
void print(string s) const;
bool equals(const gtsam::Values& other, double tol) const;
void insert(size_t j, const gtsam::Value& value);
template<class T = {
gtsam::Point2,
gtsam::Point3,
gtsam::Rot2,
gtsam::Pose2,
gtsam::Rot3,
gtsam::Pose3,
gtsam::Cal3_S2,
gtsam::Cal3DS2}>
void insert(size_t j, const T& value);
void insert(const gtsam::Values& values);
void update(const gtsam::Values& values);
void erase(size_t j);
@ -1704,6 +1693,18 @@ class Values {
// void update(size_t j, const gtsam::Value& val);
void insert(size_t j, const gtsam::Pose2& t);
void update(size_t j, const gtsam::Pose2& t);
// But it would be nice if this worked:
// template<class T = {
// gtsam::Point2,
// gtsam::Point3,
// gtsam::Rot2,
// gtsam::Pose2,
// gtsam::Rot3,
// gtsam::Pose3,
// gtsam::Cal3_S2,
// gtsam::Cal3DS2}>
// void insert(size_t j, const T& value);
};
// Actually a FastList<Key>