Added Vectors and Matrices. Does not work yet.

release/4.3a0
krunalchande 2014-11-26 03:54:21 -05:00
parent e842c9adbc
commit 7a0366684a
1 changed files with 8 additions and 2 deletions

10
gtsam.h
View File

@ -1738,6 +1738,8 @@ class Values {
void insert(size_t j, const gtsam::Cal3Bundler& t); void insert(size_t j, const gtsam::Cal3Bundler& t);
void insert(size_t j, const gtsam::EssentialMatrix& t); void insert(size_t j, const gtsam::EssentialMatrix& t);
void insert(size_t j, const gtsam::imuBias::ConstantBias& t); void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
void insert(size_t j, Vector t);
void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of sizeof to incomplete type boost::STATIC_ASSERTION_FAILURE<false>
void update(size_t j, const gtsam::Point2& t); void update(size_t j, const gtsam::Point2& t);
void update(size_t j, const gtsam::Point3& t); void update(size_t j, const gtsam::Point3& t);
@ -1750,9 +1752,11 @@ class Values {
void update(size_t j, const gtsam::Cal3Bundler& t); void update(size_t j, const gtsam::Cal3Bundler& t);
void update(size_t j, const gtsam::EssentialMatrix& t); void update(size_t j, const gtsam::EssentialMatrix& t);
void update(size_t j, const gtsam::imuBias::ConstantBias& t); void update(size_t j, const gtsam::imuBias::ConstantBias& t);
void update(size_t j, Vector t);
void update(size_t j, Matrix t);
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2,
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias}> gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias ,Vector, Matrix}> // Parse Error
T at(size_t j); T at(size_t j);
}; };
@ -2150,7 +2154,9 @@ class NonlinearISAM {
#include <gtsam/geometry/StereoPoint2.h> #include <gtsam/geometry/StereoPoint2.h>
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
template<T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2, gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias}> template<T = { gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,
gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias, Vector, Matrix }> // Parse Error
virtual class PriorFactor : gtsam::NoiseModelFactor { virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
T prior() const; T prior() const;